StateGraphParser.cpp
Go to the documentation of this file.
00001 /***************************************************************************
00002   tag: Peter Soetens  Mon May 10 19:10:37 CEST 2004  StateGraphParser.cxx
00003 
00004                         StateGraphParser.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 "StateGraphParser.hpp"
00031 #include "CommonParser.hpp"
00032 #include "ConditionParser.hpp"
00033 #include "ConditionCompare.hpp"
00034 #include "ConditionComposite.hpp"
00035 #include "ConditionCache.hpp"
00036 #include "ConditionBoolDataSource.hpp"
00037 #include "ValueChangeParser.hpp"
00038 #include "ProgramGraphParser.hpp"
00039 #include "PeerParser.hpp"
00040 #include "ArgumentsParser.hpp"
00041 #include "StateMachineBuilder.hpp"
00042 #include "../TaskContext.hpp"
00043 #include "StateMachineService.hpp"
00044 
00045 #include "CommandComposite.hpp"
00046 #include "../internal/Exceptions.hpp"
00047 #include "../base/AttributeBase.hpp"
00048 #include "ConditionTrue.hpp"
00049 #include "ConditionInvert.hpp"
00050 #include "StateDescription.hpp"
00051 #include "ParsedStateMachine.hpp"
00052 
00053 #include <iostream>
00054 #include <functional>
00055 #include <algorithm>
00056 #include <boost/bind.hpp>
00057 #include <boost/lambda/lambda.hpp>
00058 #include <boost/call_traits.hpp>
00059 #include <iostream>
00060 #include <memory>
00061 #include "../internal/mystd.hpp"
00062 
00063 namespace RTT
00064 {
00065     using namespace boost;
00066     using namespace detail;
00067     using boost::bind;
00068 
00069     using namespace std;
00070 
00071     namespace {
00072         enum GraphSyntaxErrors
00073         {
00074             state_expected,
00075             handle_expected,
00076             transition_expected,
00077         };
00078 
00079         boost::spirit::classic::assertion<GraphSyntaxErrors> expect_state(state_expected);
00080         boost::spirit::classic::assertion<GraphSyntaxErrors> expect_handle(handle_expected);
00081         boost::spirit::classic::assertion<GraphSyntaxErrors> expect_transition(transition_expected);
00082         boost::spirit::classic::assertion<std::string> expect_end("Ending '}' expected ( or could not find out what this line means ).");
00083         boost::spirit::classic::assertion<std::string> expect_end_of_state("Exptected ending '}' at end of state ( or could not find out what this line means ).");
00084         boost::spirit::classic::assertion<std::string> expect_if("Wrongly formatted \"if ... then select\" clause.");
00085         boost::spirit::classic::assertion<std::string> expect_select("'select' statement required after emty transition program.");
00086         boost::spirit::classic::assertion<std::string> expect_select_ident("'select' requires a valid state name.");
00087         boost::spirit::classic::assertion<std::string> expect_comma("Expected a comma separator.");
00088         boost::spirit::classic::assertion<std::string> expect_ident("Expected a valid identifier.");
00089         boost::spirit::classic::assertion<std::string> expect_event_or_if("Expected an event name or an if clause in transition statement.");
00090         boost::spirit::classic::assertion<std::string> expect_open("Open brace expected.");
00091         boost::spirit::classic::assertion<std::string> expect_eof("Invalid input in file.");
00092         boost::spirit::classic::assertion<std::string> expect_eol("Newline expected at end of statement.");
00093         boost::spirit::classic::assertion<std::string> expect_semicolon("Semi colon expected after statement.");
00094         boost::spirit::classic::assertion<std::string> expect_open_parenth( "Open parenthesis expected." );
00095         boost::spirit::classic::assertion<std::string> expect_close_parenth( "Open parenthesis expected." );
00096         boost::spirit::classic::assertion<std::string> expect_eventselect("'select' statement required after event or transition program.");
00097         boost::spirit::classic::assertion<std::string> expect_eventargs("Could not parse arguments after event.");
00098     }
00099 
00100 
00101     StateGraphParser::StateGraphParser( iter_t& positer,
00102                                         TaskContext* tc, ExecutionEngine* tcaller, CommonParser* cp )
00103         : context( tc ),
00104           caller( tcaller ),
00105           mpositer( positer ),
00106           ln_offset(0),
00107           curtemplate(),
00108           curinstantiatedmachine(),
00109           curmachinebuilder( 0 ),
00110           curinitialstateflag( false ),
00111           curfinalstateflag( false ),
00112           curstate( 0 ),
00113           curnonprecstate( 0 ),
00114           progParser( 0 ),
00115           elsestate(0),
00116           curcondition( 0 ),
00117           isroot(false),
00118           selectln(0),
00119           evname(""),
00120           commonparser( cp ),
00121           conditionparser( new ConditionParser( context, caller, *commonparser ) ),
00122           valuechangeparser( new ValueChangeParser(context, *commonparser, context->provides(), caller) ),
00123           expressionparser( new ExpressionParser(context, caller, *commonparser) ),
00124           argsparser(0),
00125           peerparser( new PeerParser(context, *commonparser, true) ) // full-path peer parser for events.
00126     {
00127         BOOST_SPIRIT_DEBUG_RULE( production );
00128         BOOST_SPIRIT_DEBUG_RULE( body );
00129         BOOST_SPIRIT_DEBUG_RULE( rootmachineinstantiation );
00130         BOOST_SPIRIT_DEBUG_RULE( statemachine );
00131         BOOST_SPIRIT_DEBUG_RULE( machineinstantiation );
00132         BOOST_SPIRIT_DEBUG_RULE( statemachinecontent );
00133         BOOST_SPIRIT_DEBUG_RULE( varline );
00134         BOOST_SPIRIT_DEBUG_RULE( state );
00135         BOOST_SPIRIT_DEBUG_RULE( vardec );
00136         BOOST_SPIRIT_DEBUG_RULE( subMachinedecl );
00137         BOOST_SPIRIT_DEBUG_RULE( statecontent );
00138         BOOST_SPIRIT_DEBUG_RULE( statecontentline );
00139         BOOST_SPIRIT_DEBUG_RULE( entry );
00140         BOOST_SPIRIT_DEBUG_RULE( preconditions );
00141         BOOST_SPIRIT_DEBUG_RULE( precondition );
00142         BOOST_SPIRIT_DEBUG_RULE( handle );
00143         BOOST_SPIRIT_DEBUG_RULE( transitions );
00144         BOOST_SPIRIT_DEBUG_RULE( transition );
00145         BOOST_SPIRIT_DEBUG_RULE( exit );
00146         BOOST_SPIRIT_DEBUG_RULE( transline );
00147         BOOST_SPIRIT_DEBUG_RULE( eventline );
00148         BOOST_SPIRIT_DEBUG_RULE( ifbranch );
00149         BOOST_SPIRIT_DEBUG_RULE( elsebranch );
00150         BOOST_SPIRIT_DEBUG_RULE( progselect );
00151         BOOST_SPIRIT_DEBUG_RULE( program );
00152         BOOST_SPIRIT_DEBUG_RULE( selector );
00153         BOOST_SPIRIT_DEBUG_RULE( machineinstarguments );
00154         BOOST_SPIRIT_DEBUG_RULE( machineinstargument );
00155         BOOST_SPIRIT_DEBUG_RULE( machinememvar );
00156         BOOST_SPIRIT_DEBUG_RULE( machinevariable );
00157         BOOST_SPIRIT_DEBUG_RULE( machineparam );
00158         BOOST_SPIRIT_DEBUG_RULE( machineconstant );
00159         BOOST_SPIRIT_DEBUG_RULE( machinealias );
00160         BOOST_SPIRIT_DEBUG_RULE( subMachinevarchange );
00161 
00162         storeOffset();
00163 
00164         production = *body >> expect_eof(end_p);
00165 
00166         body = statemachine[ boost::bind( &StateGraphParser::seenstatemachineend, this ) ][boost::bind( &StateGraphParser::saveText, this, _1, _2)]
00167                          | rootmachineinstantiation;
00168 
00169 
00170         rootmachineinstantiation =
00171             keyword_p("RootMachine")[boost::bind (&StateGraphParser::startrootmachineinstantiation, this) ]
00172             >> machineinstantiation[ boost::bind( &StateGraphParser::seenrootmachineinstantiation, this ) ];
00173 
00174         statemachine =
00175             keyword_p("StateMachine") //[boost::bind( &StateGraphParser::storeOffset, this)]
00176             >> expect_ident( commonparser->identifier[ boost::bind( &StateGraphParser::seenstatemachinename, this, _1, _2 )] )
00177             >> expect_open( ch_p( '{' ) )
00178             >> statemachinecontent
00179             >> expect_end( ch_p( '}' ) );
00180 
00181         // Zero or more declarations and Zero or more states. Once a state is encountered, no more global transitions may be defined.
00182         statemachinecontent = *( varline | transitions | transition) >> *( varline | state);
00183 
00184         varline = vardec[lambda::var(commonparser->skipeol) = false] >> commonparser->eos[lambda::var(commonparser->skipeol) = true];
00185 
00186         vardec = subMachinedecl | machinememvar | machineparam;
00187 
00188         machinememvar = ( machineconstant | machinevariable | machinealias )[boost::bind( &StateGraphParser::seenmachinevariable, this )];
00189         machineconstant = valuechangeparser->constantDefinitionParser();
00190         machinevariable = valuechangeparser->variableDefinitionParser();
00191         machinealias = valuechangeparser->aliasDefinitionParser();
00192 
00193         machineparam = valuechangeparser->paramDefinitionParser()[boost::bind( &StateGraphParser::seenmachineparam, this )];
00194 
00195         subMachinedecl = keyword_p("SubMachine")
00196                          >> machineinstantiation[boost::bind( &StateGraphParser::seensubMachineinstantiation, this )];
00197 
00198         machineinstantiation =
00199             expect_ident( commonparser->identifier[ boost::bind( &StateGraphParser::seenmachinetypename, this, _1, _2 )] )
00200             >> expect_ident( commonparser->identifier[ boost::bind( &StateGraphParser::seeninstmachinename, this, _1, _2 )] )
00201             >> ( ! ( ch_p( '(' )
00202                      >> !machineinstarguments
00203                      >> expect_close_parenth( ch_p( ')' ) ) ) )[ boost::bind( &StateGraphParser::seenmachineinstantiation, this )];
00204 
00205         machineinstarguments =
00206             machineinstargument >> *( ',' >> machineinstargument );
00207 
00208         machineinstargument =
00209             commonparser->identifier[ boost::bind( &StateGraphParser::seenmachineinstargumentname, this, _1, _2 )]
00210             >> '='
00211             >> expressionparser->parser()[ boost::bind( &StateGraphParser::seenmachineinstargumentvalue, this )];
00212 
00213         state =
00214           !( keyword_p( "initial" )[boost::bind( &StateGraphParser::seeninitialstate,this )]
00215              | keyword_p( "final" )[boost::bind( &StateGraphParser::seenfinalstate,this )] )
00216           >> keyword_p( "state" )
00217           >> expect_ident(commonparser->identifier[ boost::bind( &StateGraphParser::statedef, this, _1, _2 ) ])
00218           >> expect_open(ch_p( '{' ))
00219           >> statecontent
00220           >> expect_end_of_state(ch_p( '}' ))[ boost::bind( &StateGraphParser::seenstateend, this ) ];
00221 
00222         // the content of a program can be any number of lines
00223         // a line is not strictly defined in the sense of text-line.
00224         statecontent = *statecontentline;
00225 
00226         // a state can contain various programs and variable definitions
00227         statecontentline =
00228             entry
00229             | preconditions
00230             | run
00231             | handle
00232             | transitions
00233             | transition
00234             | exit
00235             | (machinememvar[lambda::var(commonparser->skipeol) = false] >> commonparser->eos[lambda::var(commonparser->skipeol) = true]);
00236 
00237         precondition = keyword_p( "precondition")
00238             >> conditionparser->parser()[ boost::bind( &StateGraphParser::seenprecondition, this)] ;
00239 
00240         preconditions = (keyword_p( "preconditions" )[ boost::bind( &StateGraphParser::inpreconditions, this )]
00241                         >> expect_open( ch_p( '{' ))
00242                         >> *transline[boost::bind(&StateGraphParser::seenendcondition,this)]
00243                         >> expect_end( ch_p( '}' ) )[
00244                             boost::bind( &StateGraphParser::seenpreconditions, this )]) | precondition;
00245 
00246         entry = keyword_p( "entry" )[ boost::bind( &StateGraphParser::inprogram, this, "entry" )]
00247                 >> expect_open(ch_p('{'))>> programBody >> expect_end(ch_p('}'))[
00248                     boost::bind( &StateGraphParser::seenentry, this )];
00249 
00250         run = keyword_p( "run" )[ boost::bind( &StateGraphParser::inprogram, this, "run" )]
00251                  >> expect_open(ch_p('{'))>> programBody >> expect_end(ch_p('}'))[
00252                      boost::bind( &StateGraphParser::seenrun, this )];
00253 
00254         exit = keyword_p( "exit" )[ boost::bind( &StateGraphParser::inprogram, this, "exit" )]
00255                >> expect_open(ch_p('{')) >> programBody >> expect_end(ch_p('}'))[
00256                    boost::bind( &StateGraphParser::seenexit, this )];
00257 
00258         handle = keyword_p( "handle" )[ boost::bind( &StateGraphParser::inprogram, this, "handle" )]
00259                  >> expect_open(ch_p('{'))>> programBody >> expect_end(ch_p('}'))[
00260                      boost::bind( &StateGraphParser::seenhandle, this )];
00261 
00262         // formal:
00263         // transition [event] [[ {program} ][ select s]] | [ if c then ][ {program} ][select s][ else [ {program} ][select s]]
00264         // parsed:
00265         // transition [ [if c then ][ {program} ][select s][ else [ {program} ][select s]]]
00266         //          | [ event [[ {program} ][ select s]] | [ if c then ][ {program} ][select s][ else [ {program} ][select s]] ]
00267         // rules:
00268         // transition = "transition" >> (transline | eventline)
00269         // transline  = progselect
00270         //            | (ifbranch >> !elsebranch)
00271         // eventline  = eventname >> transline
00272         // progselect = (selector | (program >> !selector))
00273         // ifbranch   = "if" >> c >> "then" >> progselect
00274         // elsebranch = "else" >> progselect
00275         // selector   = "select" >> ...
00276         // program    = "{" >> ...
00277         //
00278 
00279         // old transition statements
00280         // the order of rule "transition" vs "transitions" is important
00281         transitions = ( keyword_p( "transitions" )
00282                         >> expect_open(ch_p('{'))
00283                         >> *((transline|eventline)[boost::bind(&StateGraphParser::seenendcondition,this)])
00284                         >> expect_end(ch_p('}')) );
00285 
00286         // new transition statements
00287         transition = keyword_p("transition") >> expect_event_or_if( transline | eventline )[boost::bind(&StateGraphParser::seenendcondition,this)];
00288         transline  = progselect | (ifbranch >> !elsebranch);
00289 
00290         // @todo: capturing events are only on local ports ?!.
00291         eventline  =
00292             !peerparser->parser() >> commonparser->identifier[ boost::bind( &StateGraphParser::seeneventname, this,_1,_2)]
00293             >> expect_eventargs(argslist[ boost::bind( &StateGraphParser::seeneventargs, this)])
00294             >> expect_eventselect(transline[ boost::bind( &StateGraphParser::seeneventtrans, this)]);
00295 
00296         progselect = selector | (program >> (selector | eps_p[boost::bind( &StateGraphParser::noselect, this )] ));
00297         // | eps_p[boost::bind( &StateGraphParser::noselect, this )] ); // if eos fails skipeol stays false !, see clear() !
00298 
00299         ifbranch = keyword_p( "if") >> conditionparser->parser()[ boost::bind( &StateGraphParser::seencondition, this)]
00300                                 >> !keyword_p( "then" )
00301                                 >> progselect;
00302         elsebranch = keyword_p("else")[boost::bind( &StateGraphParser::seenelse, this )]
00303             >> progselect;
00304 
00305         program =
00306             ch_p('{')[ boost::bind( &StateGraphParser::inprogram, this, "transition" )]
00307                 >> programBody
00308                 >> expect_end(ch_p('}'))[boost::bind( &StateGraphParser::seentransprog, this )];
00309 
00310         selector =  keyword_p( "select" ) >> expect_select_ident(( commonparser->identifier[ boost::bind( &StateGraphParser::seenselect, this, _1, _2) ]
00311                                           >> *(keyword_p("or") >> commonparser->identifier[ boost::bind( &StateGraphParser::seenselect, this, _1, _2) ])
00312                                           )[lambda::var(commonparser->skipeol) = false]
00313                                                        >> commonparser->eos[lambda::var(commonparser->skipeol) = true]);
00314 
00315     }
00316 
00317     rule_t& StateGraphParser::parser() {
00318         return body;
00319     }
00320 
00321     ParsedStateMachinePtr StateGraphParser::getParserResult() {
00322         ParsedStateMachinePtr ret;
00323         if ( rootmachines.empty() )
00324             return ret;
00325         std::vector<ParsedStateMachinePtr> vret = values( rootmachines );
00326         rootmachines.clear();
00327         return vret.front();
00328     }
00329 
00330 
00331     void StateGraphParser::seeninitialstate()
00332     {
00333         curinitialstateflag = true;
00334     }
00335 
00336     void StateGraphParser::seenfinalstate()
00337     {
00338         curfinalstateflag = true;
00339     }
00340 
00341     void StateGraphParser::statedef( iter_t s, iter_t f)
00342     {
00343         assert( !curstate );
00344 
00345         std::string def(s, f);
00346         if ( curtemplate->getState( def ) != 0 )
00347         {
00348             assert( dynamic_cast<StateDescription*>( curtemplate->getState( def ) ) );
00349             StateDescription* existingstate = static_cast<StateDescription*>( curtemplate->getState( def ) );
00350             if ( existingstate->isDefined() )
00351                 ORO_THROW(parse_exception_semantic_error("state " + def + " redefined.") );
00352             else
00353                 curstate = existingstate;
00354             curstate->setEntryPoint( mpositer.get_position().line - ln_offset );
00355         }
00356         else
00357         {
00358             curstate = new StateDescription(def, mpositer.get_position().line - ln_offset ); // create an empty state
00359             curtemplate->addState( curstate );
00360         }
00361 
00362     }
00363 
00364     void StateGraphParser::seenstateend()
00365     {
00366         if ( curinitialstateflag )
00367         {
00368             if ( curtemplate->getInitialState() )
00369                 ORO_THROW(parse_exception_semantic_error( "Attempt to define more than one initial state." ));
00370             else curtemplate->setInitialState( curstate );
00371         }
00372         if ( curfinalstateflag )
00373         {
00374             if ( curtemplate->getFinalState() )
00375                 ORO_THROW(parse_exception_semantic_error( "Attempt to define more than one final state." ));
00376             else curtemplate->setFinalState( curstate );
00377         }
00378 
00379         assert( curstate );
00380         curstate->setDefined( true );
00381         curstate = 0;
00382         curinitialstateflag = false;
00383         curfinalstateflag = false;
00384         // clear all port-triggered transitions for this state.
00385         cur_port_events.clear();
00386     }
00387 
00388     void StateGraphParser::inprogram(const std::string& name)
00389     {
00390         // setup the progParser to parse the program body,
00391         // dynamically assign this parser to body.
00392         assert( progParser != 0 );
00393         // program name, stack, line offset.
00394         //cerr << "SGP : Stack is " << curobject->getName() <<endl;
00395         progParser->initBodyParser( name, curobject, ln_offset );
00396 
00397         programBody = progParser->bodyParser();
00398     }
00399 
00400     ProgramInterfacePtr StateGraphParser::finishProgram()
00401     {
00402         return progParser->bodyParserResult();
00403     }
00404 
00405     void StateGraphParser::seenentry()
00406     {
00407         if ( curstate->getEntryProgram() )
00408             ORO_THROW( parse_exception_semantic_error( "Attempt to define entry twice in state "+ curstate->getName() ));
00409         curstate->setEntryProgram( finishProgram() );
00410     }
00411 
00412     void StateGraphParser::seenexit()
00413     {
00414         if ( curstate->getExitProgram() )
00415             ORO_THROW( parse_exception_semantic_error( "Attempt to define exit twice in state "+ curstate->getName() ));
00416         curstate->setExitProgram( finishProgram() );
00417     }
00418 
00419     void StateGraphParser::seenhandle()
00420     {
00421         if ( curstate->getHandleProgram() )
00422             ORO_THROW( parse_exception_semantic_error( "Attempt to define handle twice in state "+ curstate->getName() ));
00423         curstate->setHandleProgram( finishProgram() );
00424     }
00425 
00426     void StateGraphParser::seenrun()
00427     {
00428         if ( curstate->getRunProgram() )
00429             ORO_THROW( parse_exception_semantic_error( "Attempt to define run twice in state "+ curstate->getName() ));
00430         curstate->setRunProgram( finishProgram() );
00431     }
00432 
00433     void StateGraphParser::seentransprog()
00434     {
00435         transProgram = finishProgram();
00436     }
00437 
00438     void StateGraphParser::seenelseprog()
00439     {
00440         // reuse transProgram to store else progr. See seenselect().
00441         //transProgram = finishProgram();
00442         //transProgram->setProgramProcessor(curtemplate->getService()->engine()->programs());
00443     }
00444 
00445     void StateGraphParser::seenelse()
00446     {
00447         assert( curcondition);
00448         curcondition = new ConditionInvert( curcondition );
00449     }
00450 
00451     void StateGraphParser::seencondition()
00452     {
00453         assert( !curcondition );
00454         curcondition = conditionparser->getParseResult();
00455         assert( curcondition );
00456         conditionparser->reset();
00457         selectln = mpositer.get_position().line - ln_offset;
00458     }
00459 
00460     void StateGraphParser::seeneventname(iter_t s, iter_t f)
00461     {
00462         evname = string(s,f);
00463 
00464         // seenselect() will use evname to see if event is causing transition
00465         assert(evname.length());
00466         peer    = peerparser->taskObject();
00467         peerparser->reset();
00468 
00469         // check if it's an operation:
00470         if (peer->hasOperation(evname) ) {
00471             argsparser =
00472                 new ArgumentsParser( *expressionparser, context, peer->provides(),
00473                                      evname, "callback" );
00474         } else {
00475             // check if it's a port.
00476             if ( peer->hasService(evname) == false || peer->getService(evname)->hasOperation("read") == false) {
00477                 if (curstate)
00478                     ORO_THROW( parse_exception_fatal_semantic_error("In state "+curstate->getName()+": InputPort or Operation "+evname+" not found in Task "+peer->getName() ));
00479                 else
00480                     ORO_THROW( parse_exception_fatal_semantic_error("In statemachine: InputPort or Operation "+evname+" not found in Task "+peer->getName() ));
00481             }
00482             argsparser =
00483                 new ArgumentsParser( *expressionparser, context, peer->getService(evname),
00484                                      evname, "read" );
00485         }
00486 
00487         argslist = argsparser->parser();
00488     }
00489 
00490     void StateGraphParser::seeneventargs()
00491     {
00492         evargs = argsparser->result();
00493         delete argsparser;
00494         argsparser = 0;
00495     }
00496 
00497     void StateGraphParser::noselect()
00498     {
00499         // if omitted, implicitly re-enter current state.
00500         if (curstate)
00501             doselect( curstate->getName() );
00502         else
00503             doselect(""); // global events/transitions
00504     }
00505 
00506     void StateGraphParser::seenselect( iter_t s, iter_t f)
00507     {
00508         std::string state_id(s,f);
00509         doselect(state_id);
00510     }
00511 
00512     void StateGraphParser::doselect( const std::string& state_id )
00513     {
00514         StateInterface* next_state = 0;
00515         if ( !state_id.empty() ) {
00516             if ( curtemplate->getState( state_id ) != 0 )
00517             {
00518                 next_state = curtemplate->getState( state_id );
00519             }
00520             else
00521             {
00522                 next_state = new StateDescription(state_id, 1); // create an empty state
00523                 curtemplate->addState( next_state );
00524             }
00525             assert( next_state );
00526         }
00527 
00528         // this transition has a lower priority than the previous one
00529         if ( selectln == 0)
00530             selectln = mpositer.get_position().line - ln_offset;
00531 
00532         if (evname.empty()) {
00533             if (curcondition == 0)
00534                 curcondition = new ConditionTrue;
00535         } else if ( peer->hasService(evname) && peer->getService(evname)->hasOperation("read") ) { // is a port
00536             try {
00537                 assert(peer->hasService(evname)); // checked in seeneventname()
00538                 ConditionInterface* evcondition = 0;
00539                 if ( global_port_events.count(evname) ){
00540                     // clone the cached condition in order to avoid a second read on the port.
00541                     evcondition = new ConditionBoolDataSource( global_port_events[evname]->getResult().get() );
00542                 } else
00543                 if ( cur_port_events.count(evname) ){
00544                     // clone the cached condition in order to avoid a second read on the port.
00545                     evcondition = new ConditionBoolDataSource( cur_port_events[evname]->getResult().get() );
00546                 } else {
00547                     // combine the implicit 'read(arg) == NewData' with the guard, if any.
00548                     DataSourceBase::shared_ptr read_dsb = peer->getService(evname)->produce("read", evargs, context->engine() );
00549                     DataSource<FlowStatus>* read_ds = dynamic_cast<DataSource<FlowStatus>*>(read_dsb.get());
00550                     assert(read_ds);
00551                     evcondition = new ConditionCompare<FlowStatus,std::equal_to<FlowStatus> >( new ConstantDataSource<FlowStatus>(NewData), read_ds );
00552                     if (curstate) {
00553                         cur_port_events[evname] = new ConditionCache( evcondition ); // caches result until reset().
00554                         evcondition = cur_port_events[evname]->clone();
00555                     } else {
00556                         //global event:
00557                         global_port_events[evname] = new ConditionCache( evcondition ); // caches result until reset().
00558                         evcondition = global_port_events[evname]->clone();
00559                     }
00560                 }
00561                 if (curcondition == 0) {
00562                     curcondition = evcondition;
00563                 } else {
00564                     curcondition = new ConditionBinaryCompositeAND( evcondition, curcondition );
00565                 }
00566             }
00567             catch( const wrong_number_of_args_exception& e )
00568                 {
00569                     throw parse_exception_wrong_number_of_arguments
00570                         ( peer->getName(), evname + ".read", e.wanted, e.received );
00571                 }
00572             catch( const wrong_types_of_args_exception& e )
00573                 {
00574                     throw parse_exception_wrong_type_of_argument
00575                         ( peer->getName(), evname + ".read", e.whicharg, e.expected_, e.received_ );
00576                 }
00577             elsestate = 0;
00578             elseProgram.reset();
00579         } else { // is an operation
00580             assert( peer->provides()->hasMember(evname) );
00581             bool res;
00582             if (curcondition == 0)
00583                 curcondition = new ConditionTrue;
00584 
00585             //             if ( elsestate != 0)
00586             //                 res = curtemplate->createEventTransition( &(peer->eventService), evname, evargs, curstate, next_state, curcondition->clone()
00587             //             else
00588             //cerr << "Registering "<<evname<<" handler for SM."<<endl;
00589             try {
00590                 res = curtemplate->createEventTransition( peer->provides(), evname, evargs, curstate, next_state, curcondition->clone(), transProgram );
00591                 if (!res)
00592                     throw parse_exception_fatal_semantic_error("StateMachine could not install a Signal Handler for Operation "+evname);
00593             }
00594             catch( const wrong_number_of_args_exception& e )
00595                 {
00596                     throw parse_exception_wrong_number_of_arguments
00597                         ( peer->getName(), evname, e.wanted, e.received );
00598                 }
00599             catch( const wrong_types_of_args_exception& e )
00600                 {
00601                     throw parse_exception_wrong_type_of_argument
00602                         ( peer->getName(), evname, e.whicharg, e.expected_, e.received_ );
00603                 }
00604             catch( const no_asynchronous_operation_exception& e )
00605                 {
00606                     throw parse_exception_fatal_semantic_error("StateMachine can't create EventTransition on Operation '" + evname + "' since it was not added with addEventOperation()." );
00607                 }
00608             catch( ... )
00609                 {
00610                     assert( false );
00611                 }
00612 
00613             assert( res ); // checked in seeneventname()
00614             elsestate = 0;
00615             elseProgram.reset();
00616             return; // we installed the Signal Handler !
00617         }
00618         // finally, install the handler:
00619         curtemplate->transitionSet( curstate, next_state, curcondition->clone(), transProgram, rank--, selectln );
00620     }
00621 
00622     void StateGraphParser::seenendcondition() {
00623         delete curcondition;
00624         curcondition = 0;
00625         selectln = 0;
00626         transProgram.reset();
00627     }
00628 
00629     void StateGraphParser::seeneventtrans() {
00630         // cleanup all event related state.
00631         evname.clear();
00632         evargs.clear();
00633     }
00634 
00635     void StateGraphParser::seenprecondition()
00636     {
00637         assert( !curcondition );
00638         curcondition = conditionparser->getParseResult();
00639         assert( curcondition );
00640         conditionparser->reset();
00641         selectln = mpositer.get_position().line - ln_offset;
00642 
00643         curtemplate->preconditionSet(curstate, curcondition, selectln );
00644         selectln = 0;
00645         curcondition = 0;
00646     }
00647 
00648 
00649     void StateGraphParser::seenstatemachineend()
00650     {
00651         assert( curtemplate );
00652         assert( ! curstate );
00653 
00654         // reclaim the defined variables:
00655 
00656 
00657         // Check if the Initial and Final States are ok.
00658         if ( curtemplate->getInitialState() == 0 )
00659             ORO_THROW( parse_exception_semantic_error("No initial state defined."));
00660         if ( curtemplate->getFinalState() == 0 )
00661             ORO_THROW( parse_exception_semantic_error("No final state defined."));
00662 
00663         if ( curtemplate->getStateList().empty() )
00664             ORO_THROW( parse_exception_semantic_error("No states defined in this state machine !"));
00665 
00666         // Check if all States are defined.
00667         vector<string> states = curtemplate->getStateList();
00668         for( vector<string>::const_iterator it = states.begin(); it != states.end(); ++it)
00669         {
00670             assert( dynamic_cast<StateDescription*>( curtemplate->getState( *it ) ) );
00671             StateDescription* sd = static_cast<StateDescription*>( curtemplate->getState( *it ) );
00672             if ( !sd->isDefined() )
00673                 ORO_THROW( parse_exception_semantic_error("State " + *it + " not defined, but referenced to."));
00674         }
00675 
00676         // retrieve _all_ defined variables and parameters, store them and cleanup the
00677         // valuechangeparser.
00678         valuechangeparser->store( curtemplate->getService() );
00679         valuechangeparser->reset();
00680 
00681         // prepend the commands for initialising the subMachine
00682         // variables..
00683         assert( curtemplate->getInitCommand() == 0);
00684         if ( varinitcommands.size() > 1 )
00685             {
00686                 CommandComposite* comcom = new CommandComposite;
00687                 for ( std::vector<ActionInterface*>::iterator i = varinitcommands.begin();
00688                       i != varinitcommands.end(); ++i )
00689                     comcom->add( *i );
00690                 curtemplate->setInitCommand( comcom );
00691             }
00692         else if (varinitcommands.size() == 1 )
00693             curtemplate->setInitCommand( *varinitcommands.begin() );
00694 
00695         varinitcommands.clear();
00696 
00697         // remove temporary subMachine peers from current task.
00698         for( StateMachine::ChildList::const_iterator it= curtemplate->getChildren().begin();
00699              it != curtemplate->getChildren().end(); ++it ) {
00700             ParsedStateMachine* psc = dynamic_cast<ParsedStateMachine*>( it->get() );
00701             if (psc) {
00702                 // remove from parent
00703                 context->provides()->removeService( psc->getService()->getName() );
00704             }
00705 
00706         }
00707 
00708         // finally :
00709         curtemplate->finish();
00710 
00711         delete progParser;
00712         progParser = 0;
00713 
00714         StateMachineBuilder* scb = new StateMachineBuilder( curtemplate );
00715         machinebuilders[curmachinename] = scb;
00716 
00717         // save curmachinename for saveText.
00718         curobject.reset();
00719         curtemplate.reset();
00720     }
00721 
00722     std::vector<ParsedStateMachinePtr> StateGraphParser::parse( iter_t& begin, iter_t end )
00723     {
00724         //skip_parser_t skip_parser = SKIP_PARSER;
00725         //iter_pol_t iter_policy( skip_parser );
00726                 //#define SKIP_PARSER
00727       skip_parser_t skip_parser = comment_p( "#" ) | comment_p( "//" ) | comment_p( "/*", "*/" ) | (space_p - eol_p) | commonparser->skipper;
00728       iter_pol_t iter_policy( skip_parser );
00729         scanner_pol_t policies( iter_policy );
00730         scanner_t scanner( begin, end, policies );
00731 
00732         // reset the condition-transition priority.
00733         rank = 0;
00734 
00735         this->storeOffset();
00736 
00737         try {
00738             if ( ! production.parse( scanner ) )
00739             {
00740                 // on error, we clear all remaining data, cause we can't
00741                 // guarantee consistency...
00742                 clear();
00743                 throw file_parse_exception(
00744                     new parse_exception_syntactic_error( "Syntax error" ),
00745                     mpositer.get_position().file, mpositer.get_position().line,
00746                     mpositer.get_position().column );
00747             }
00748             std::vector<ParsedStateMachinePtr> ret = values( rootmachines );
00749             rootmachines.clear();
00750             return ret;
00751         }
00752         catch( const parser_error<std::string, iter_t>& e )
00753         {
00754             // on error, we clear all remaining data, cause we can't
00755             // guarantee consistency...
00756             clear();
00757             throw file_parse_exception(
00758                 new parse_exception_syntactic_error( e.descriptor ),
00759                 mpositer.get_position().file, mpositer.get_position().line,
00760                 mpositer.get_position().column );
00761         }
00762         catch( const parser_error<GraphSyntaxErrors, iter_t>& )
00763         {
00764             // on error, we clear all remaining data, cause we can't
00765             // guarantee consistency...
00766             clear();
00767             throw file_parse_exception(
00768                 new parse_exception_syntactic_error( "Expected one of: entry, handle, exit, transitions" ),
00769                 mpositer.get_position().file, mpositer.get_position().line,
00770                 mpositer.get_position().column );
00771         }
00772         catch( const parse_exception& e )
00773         {
00774             // on error, we clear all remaining data, cause we can't
00775             // guarantee consistency...
00776             clear();
00777             throw file_parse_exception(
00778                 e.copy(), mpositer.get_position().file,
00779                 mpositer.get_position().line, mpositer.get_position().column );
00780         }
00781 //         catch( ... ) {
00782 //             assert( false );
00783 //         }
00784     }
00785 
00786     StateGraphParser::~StateGraphParser() {
00787         clear();
00788         delete valuechangeparser;
00789         delete expressionparser;
00790         delete conditionparser;
00791         delete peerparser;
00792     }
00793 
00794     void StateGraphParser::clear() {
00795 
00796         // remove tmp vars from TaskContext
00797         valuechangeparser->reset();
00798 
00799         // in case of corrupt file, skipeol could have remained on false,
00800         // so make sure it is set correctly again
00801         commonparser->skipeol = true;
00802         selectln = 0;
00803         transProgram.reset();
00804         elseProgram.reset();
00805         delete argsparser;
00806         argsparser = 0;
00807         delete curcondition;
00808         curcondition = 0;
00809         // we own curstate, but not through this pointer...
00810         curstate = 0;
00811         delete curnonprecstate;
00812         curnonprecstate = 0;
00813         // we own curmachinebuilder, but not through this pointer...
00814         curmachinebuilder = 0;
00815         curinstantiatedmachine.reset();
00816         // If non null, there was a parse-error, undo all :
00817         if ( curtemplate )
00818         {
00819 
00820           // remove temporary subMachine peers from current task.
00821           for( StateMachine::ChildList::const_iterator it= curtemplate->getChildren().begin();
00822                it != curtemplate->getChildren().end(); ++it ) {
00823               ParsedStateMachine* psc = dynamic_cast<ParsedStateMachine*>( it->get() );
00824               if (psc && psc->getService() ) {
00825                   context->provides()->removeService( psc->getService()->getName() );
00826               }
00827           }
00828           // remove all 'this' data factories
00829           curtemplate->getService()->clear();
00830 
00831           // will also delete all children :
00832           curtemplate.reset();
00833         }
00834         // should be empty in most cases :
00835         for ( std::vector<ActionInterface*>::iterator i = varinitcommands.begin();
00836               i != varinitcommands.end(); ++ i )
00837             delete *i;
00838         varinitcommands.clear();
00839         for ( std::vector<ActionInterface*>::iterator i = paraminitcommands.begin();
00840               i != paraminitcommands.end(); ++ i )
00841             delete *i;
00842         paraminitcommands.clear();
00843         for ( machinebuilders_t::iterator i = machinebuilders.begin();
00844               i != machinebuilders.end(); ++i )
00845           delete i->second;
00846         machinebuilders.clear();
00847 
00848     }
00849 
00850     void StateGraphParser::seenstatemachinename( iter_t begin, iter_t end ) {
00851         // the 'type' of the SC :
00852         curmachinename = std::string ( begin, end );
00853 
00854         // check if the type exists already :
00855         if ( machinebuilders.count( curmachinename ) != 0 )
00856             ORO_THROW( parse_exception_semantic_error("StateMachine type " + curmachinename + " redefined."));
00857 
00858         curtemplate.reset(new ParsedStateMachine());
00859         // Connect the new SC to the relevant machines.
00860         // 'sc' acts as a stack for storing variables.
00861         curobject.reset( new StateMachineService(curtemplate, context ) );
00862         curobject->setName( curmachinename );
00863         curtemplate->setService( curobject ); // store.
00864 
00865         // we pass the plain file positer such that parse errors are
00866         // refering to correct file line numbers.
00867         progParser = new ProgramGraphParser(mpositer, context, caller, *commonparser);
00868 
00869         // set the 'type' name :
00870         curtemplate->setName( curmachinename, false );
00871     }
00872 
00873     void StateGraphParser::storeOffset() {
00874         // stores the begining of a (possible) new statemachine definition.
00875         // start line number :
00876         ln_offset = mpositer.get_position().line - 1;
00877         // start of text :
00878         saveStartPos = mpositer;
00879     }
00880 
00881     void StateGraphParser::saveText( iter_t begin, iter_t end ) {
00882         assert( curmachinename.length() != 0 );
00883         //cerr << std::string(begin, end)<<endl;
00884         if ( machinebuilders.count( curmachinename ) == 0 )
00885             return; // yes this might be possible
00886         // due to the shared-text implementation, we can set the text afterwards.
00887         machinebuilders[curmachinename]->item()->setText( std::string( saveStartPos, end) );
00888         this->storeOffset();
00889     }
00890 
00891     void StateGraphParser::inpreconditions() {
00892         // we postpone the current state
00893         assert( curnonprecstate == 0 );
00894         curnonprecstate = curstate->postponeState();
00895         // add the postponed state in PSM :
00896         curtemplate->addState( curnonprecstate );
00897     }
00898 
00899     void StateGraphParser::seenpreconditions() {
00900         curtemplate->transitionSet( curstate, curnonprecstate, new ConditionTrue, rank--, mpositer.get_position().line - ln_offset );
00901         curstate->setDefined( true );
00902         curstate = curnonprecstate;
00903         curnonprecstate = 0;
00904     }
00905 
00906     void StateGraphParser::startrootmachineinstantiation() {
00907         isroot = true;
00908     }
00909 
00910     void StateGraphParser::seenrootmachineinstantiation() {
00911         // first reset the flag.
00912         isroot = false;
00913         if( rootmachines.find( curinstmachinename ) != rootmachines.end() )
00914             ORO_THROW( parse_exception_semantic_error( "Root machine \"" + curinstmachinename + "\" already defined." ));
00915         rootmachines[curinstmachinename] = curinstantiatedmachine;
00916 
00917         // recursively set the name of this SC and all subs :
00918         // furthermore, it adds the TC of each child as peer TC to the parent.
00919         curinstantiatedmachine->setName( curinstmachinename, true );
00920 
00921         // check if the type exists already :
00922         if ( context->provides()->hasService( curinstmachinename ) )
00923             ORO_THROW( parse_exception_semantic_error("TaskContext '"+context->getName()+"' has already a Service named '" + curinstmachinename + "' ."));
00924 
00925         // Transfer ownership to the owning task.
00926         context->provides()->addService( curinstantiatedmachine->getService() );
00927 
00928         curinstantiatedmachine.reset();
00929         curinstmachinename.clear();
00930     }
00931 
00932     void StateGraphParser::seensubMachineinstantiation() {
00933         if ( find_if( curtemplate->getChildren().begin(),
00934                       curtemplate->getChildren().end(),
00935                       boost::bind( equal_to<string>(), boost::bind(&StateMachine::getName,_1), curinstmachinename )) != curtemplate->getChildren().end() )
00936             ORO_THROW( parse_exception_semantic_error( "SubMachine \"" + curinstmachinename + "\" already defined." ));
00937 
00938         // Since we parse in the task context, we must _temporarily_
00939         // make each subMachine a peer of the task so that we can access
00940         // its methods.
00941 
00942         // Warning: use context->unmountService() since curinstantiatedmachine must owns it.
00943         if ( !context->provides()->addService( curinstantiatedmachine->getService() ) )
00944             ORO_THROW( parse_exception_semantic_error(
00945                 "Name clash: name of instantiated machine \"" + curinstmachinename +
00946                 "\"  already used as object name in task '"+context->getName()+"'." ));
00947 
00948         // SM child relation
00949         curtemplate->addChild( curinstantiatedmachine );
00950         // sub-Service relation.
00951         curtemplate->getService()->addService( curinstantiatedmachine->getService() );
00952 
00953         curinstantiatedmachine->setName(curinstmachinename, false ); // not recursive !
00954 
00955         curinstantiatedmachine.reset();
00956         curinstmachinename.clear();
00957     }
00958 
00959     void StateGraphParser::seenmachinetypename( iter_t begin, iter_t end ) {
00960         assert( curmachinebuilder == 0 );
00961         std::string name( begin, end );
00962         machinebuilders_t::iterator i = machinebuilders.find( name );
00963         if ( i == machinebuilders.end() )
00964             ORO_THROW( parse_exception_semantic_error( "StateMachine \"" + name + "\" not defined." ));
00965         curmachinebuilder = i->second;
00966     }
00967 
00968     void StateGraphParser::seeninstmachinename( iter_t begin, iter_t end ) {
00969         assert( curmachinebuilder != 0 );
00970         assert( curinstmachinename.empty() );
00971         curinstmachinename = std::string( begin, end );
00972     }
00973 
00974     void StateGraphParser::seenmachineinstargumentname( iter_t begin, iter_t end ) {
00975         assert( curmachineinstargumentname.empty() );
00976         std::string name( begin, end );
00977         curmachineinstargumentname = name;
00978     }
00979 
00980     void StateGraphParser::seenmachineinstargumentvalue() {
00981         DataSourceBase::shared_ptr value = expressionparser->getResult();
00982         // let's not forget this...
00983         expressionparser->dropResult();
00984         if ( curinstmachineparams.find( curmachineinstargumentname ) != curinstmachineparams.end() )
00985             ORO_THROW( parse_exception_semantic_error(
00986                 "In initialisation of StateMachine \"" + curinstmachinename +
00987                 "\": Parameter \"" + curmachineinstargumentname +"\" initialised twice..." ));
00988         curinstmachineparams[curmachineinstargumentname] = value;
00989         curmachineinstargumentname.clear();
00990     }
00991 
00992     void StateGraphParser::seenmachineinstantiation()
00993     {
00994         // TODO : move this code to the ParsedStateMachine builder.
00995 
00996         // Create a full depth copy (including subMachines)
00997         // if RootMachine, make special copy which fixes attributes such
00998         // that on subsequent copy() they keep pointing to same var.
00999         // use shared_ptr to release on throw's below.
01000         ParsedStateMachinePtr nsc( curmachinebuilder->build( isroot ) );
01001 
01002         // we stored the attributes which are params of nsc
01003         // in the build operation :
01004         machineparams_t params = nsc->getParameters();
01005 
01006         // first run over the given parameters to see if they all exist in
01007         // the context we're instantiating...
01008         for ( machineparamvalues_t::iterator i = curinstmachineparams.begin(); i != curinstmachineparams.end(); ++i )
01009         {
01010             machineparams_t::iterator j = params.find( i->first );
01011             if ( j == params.end() )
01012                 ORO_THROW( parse_exception_semantic_error( "No parameter \"" + i->first + "\" in this StateMachine." ) );
01013         }
01014 
01015         for ( machineparams_t::iterator i = params.begin(); i != params.end(); ++i )
01016         {
01017             machineparamvalues_t::iterator j = curinstmachineparams.find( i->first );
01018             if ( j == curinstmachineparams.end() )
01019                 ORO_THROW( parse_exception_semantic_error(
01020                     "No value given for argument \"" + i->first + "\" in instantiation of this StateMachine." ));
01021 #ifndef ORO_EMBEDDED
01022             try {
01023                 paraminitcommands.push_back( i->second->getDataSource()->updateAction( j->second.get() ) );
01024             }
01025             catch( const bad_assignment& )
01026                 {
01027                     throw parse_exception_semantic_error("Attempt to initialize parameter '"+i->first+"' with a value which is of a different type." );
01028                 }
01029 #else
01030             ActionInterface* ret =  i->second->getDataSource()->updateAction( j->second.get());
01031             if (ret)
01032                 paraminitcommands.push_back( ret );
01033             else
01034                 return;
01035 #endif
01036         }
01037 
01038         curinstantiatedmachine = nsc;
01039 
01040         // prepend the commands for initialising the subMachine
01041         // parameters
01042         if ( paraminitcommands.size() > 0 )
01043             {
01044                 CommandComposite* comcom = new CommandComposite;
01045                 for ( std::vector<ActionInterface*>::iterator i = paraminitcommands.begin();
01046                       i != paraminitcommands.end(); ++i )
01047                     comcom->add( *i );
01048                 // init the vars as last (if any), so that they can be inited by an expression containing the params :
01049                 if ( curinstantiatedmachine->getInitCommand() )
01050                     comcom->add( curinstantiatedmachine->getInitCommand() );
01051                 curinstantiatedmachine->setInitCommand( comcom );
01052             }
01053         paraminitcommands.clear();
01054 
01055         curmachinebuilder = 0;
01056         curinstmachineparams.clear();
01057 
01058         // set the TaskContext name to the instance name :
01059         curinstantiatedmachine->getService()->setName(curinstmachinename );
01060     }
01061 
01062     void StateGraphParser::seenmachinevariable() {
01063         std::vector<ActionInterface*> acv = valuechangeparser->assignCommands();
01064         for(std::vector<ActionInterface*>::iterator it = acv.begin(); it!=acv.end(); ++it)
01065             varinitcommands.push_back( *it );
01066         // this only clears the last parsed variables, not the 'store' (see reset())
01067         valuechangeparser->clear();
01068     }
01069 
01070     void StateGraphParser::seenmachineparam() {
01071         std::vector<std::string> pnames = valuechangeparser->definedNames();
01072         std::vector<AttributeBase*> tbases = valuechangeparser->definedValues();
01073         assert( pnames.size() == tbases.size() );
01074         for (unsigned int i = 0; i < pnames.size(); ++i)
01075             curtemplate->addParameter( pnames[i] , tbases[i] );
01076         // this only clears the last parsed variables, not the 'store'  (see reset())
01077         valuechangeparser->clear();
01078     }
01079 
01080 
01081 }


rtt
Author(s): RTT Developers
autogenerated on Wed Aug 26 2015 16:16:18