00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include "parser-debug.hpp"
00029 #include "parse_exception.hpp"
00030 #include "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) )
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")
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
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
00223
00224 statecontent = *statecontentline;
00225
00226
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
00263
00264
00265
00266
00267
00268
00269
00270
00271
00272
00273
00274
00275
00276
00277
00278
00279
00280
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
00287 transition = keyword_p("transition") >> expect_event_or_if( transline | eventline )[boost::bind(&StateGraphParser::seenendcondition,this)];
00288 transline = progselect | (ifbranch >> !elsebranch);
00289
00290
00291 eventline = 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
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 );
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
00385 cur_port_events.clear();
00386 }
00387
00388 void StateGraphParser::inprogram(const std::string& name)
00389 {
00390
00391
00392 assert( progParser != 0 );
00393
00394
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
00441
00442
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
00465 assert(evname.length());
00466 peer = peerparser->taskObject();
00467 peerparser->reset();
00468
00469
00470 if (peer->hasOperation(evname) ) {
00471 argsparser =
00472 new ArgumentsParser( *expressionparser, context, peer->provides(),
00473 evname, "callback" );
00474 } else {
00475
00476 if ( peer->hasService(evname) == false || peer->provides(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->provides(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
00500 if (curstate)
00501 doselect( curstate->getName() );
00502 else
00503 doselect("");
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);
00523 curtemplate->addState( next_state );
00524 }
00525 assert( next_state );
00526 }
00527
00528
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->provides(evname) && peer->provides(evname)->hasOperation("read") ) {
00536 try {
00537 assert(peer->provides(evname));
00538 ConditionInterface* evcondition = 0;
00539 if ( global_port_events.count(evname) ){
00540
00541 evcondition = new ConditionBoolDataSource( global_port_events[evname]->getResult().get() );
00542 } else
00543 if ( cur_port_events.count(evname) ){
00544
00545 evcondition = new ConditionBoolDataSource( cur_port_events[evname]->getResult().get() );
00546 } else {
00547
00548 DataSourceBase::shared_ptr read_dsb = peer->provides(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 );
00554 evcondition = cur_port_events[evname]->clone();
00555 } else {
00556
00557 global_port_events[evname] = new ConditionCache( evcondition );
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 {
00580 assert( peer->provides()->hasMember(evname) );
00581 bool res;
00582 if (curcondition == 0)
00583 curcondition = new ConditionTrue;
00584
00585
00586
00587
00588
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( ... )
00605 {
00606 assert( false );
00607 }
00608
00609 assert( res );
00610 elsestate = 0;
00611 elseProgram.reset();
00612 return;
00613 }
00614
00615 curtemplate->transitionSet( curstate, next_state, curcondition->clone(), transProgram, rank--, selectln );
00616 }
00617
00618 void StateGraphParser::seenendcondition() {
00619 delete curcondition;
00620 curcondition = 0;
00621 selectln = 0;
00622 transProgram.reset();
00623 }
00624
00625 void StateGraphParser::seeneventtrans() {
00626
00627 evname.clear();
00628 evargs.clear();
00629 }
00630
00631 void StateGraphParser::seenprecondition()
00632 {
00633 assert( !curcondition );
00634 curcondition = conditionparser->getParseResult();
00635 assert( curcondition );
00636 conditionparser->reset();
00637 selectln = mpositer.get_position().line - ln_offset;
00638
00639 curtemplate->preconditionSet(curstate, curcondition, selectln );
00640 selectln = 0;
00641 curcondition = 0;
00642 }
00643
00644
00645 void StateGraphParser::seenstatemachineend()
00646 {
00647 assert( curtemplate );
00648 assert( ! curstate );
00649
00650
00651
00652
00653
00654 if ( curtemplate->getInitialState() == 0 )
00655 ORO_THROW( parse_exception_semantic_error("No initial state defined."));
00656 if ( curtemplate->getFinalState() == 0 )
00657 ORO_THROW( parse_exception_semantic_error("No final state defined."));
00658
00659 if ( curtemplate->getStateList().empty() )
00660 ORO_THROW( parse_exception_semantic_error("No states defined in this state machine !"));
00661
00662
00663 vector<string> states = curtemplate->getStateList();
00664 for( vector<string>::const_iterator it = states.begin(); it != states.end(); ++it)
00665 {
00666 assert( dynamic_cast<StateDescription*>( curtemplate->getState( *it ) ) );
00667 StateDescription* sd = static_cast<StateDescription*>( curtemplate->getState( *it ) );
00668 if ( !sd->isDefined() )
00669 ORO_THROW( parse_exception_semantic_error("State " + *it + " not defined, but referenced to."));
00670 }
00671
00672
00673
00674 valuechangeparser->store( curtemplate->getService() );
00675 valuechangeparser->reset();
00676
00677
00678
00679 assert( curtemplate->getInitCommand() == 0);
00680 if ( varinitcommands.size() > 1 )
00681 {
00682 CommandComposite* comcom = new CommandComposite;
00683 for ( std::vector<ActionInterface*>::iterator i = varinitcommands.begin();
00684 i != varinitcommands.end(); ++i )
00685 comcom->add( *i );
00686 curtemplate->setInitCommand( comcom );
00687 }
00688 else if (varinitcommands.size() == 1 )
00689 curtemplate->setInitCommand( *varinitcommands.begin() );
00690
00691 varinitcommands.clear();
00692
00693
00694 for( StateMachine::ChildList::const_iterator it= curtemplate->getChildren().begin();
00695 it != curtemplate->getChildren().end(); ++it ) {
00696 ParsedStateMachine* psc = dynamic_cast<ParsedStateMachine*>( it->get() );
00697 if (psc) {
00698
00699 context->provides()->removeService( psc->getService()->getName() );
00700 }
00701
00702 }
00703
00704
00705 curtemplate->finish();
00706
00707 delete progParser;
00708 progParser = 0;
00709
00710 StateMachineBuilder* scb = new StateMachineBuilder( curtemplate );
00711 machinebuilders[curmachinename] = scb;
00712
00713
00714 curobject.reset();
00715 curtemplate.reset();
00716 }
00717
00718 std::vector<ParsedStateMachinePtr> StateGraphParser::parse( iter_t& begin, iter_t end )
00719 {
00720
00721
00722
00723 iter_pol_t iter_policy( ( comment_p( "#" ) | comment_p( "//" ) | comment_p( "/*", "*/" ) | (space_p - eol_p) | commonparser->skipper ) );
00724 scanner_pol_t policies( iter_policy );
00725 scanner_t scanner( begin, end, policies );
00726
00727
00728 rank = 0;
00729
00730 this->storeOffset();
00731
00732 try {
00733 if ( ! production.parse( scanner ) )
00734 {
00735
00736
00737 clear();
00738 throw file_parse_exception(
00739 new parse_exception_syntactic_error( "Syntax error" ),
00740 mpositer.get_position().file, mpositer.get_position().line,
00741 mpositer.get_position().column );
00742 }
00743 std::vector<ParsedStateMachinePtr> ret = values( rootmachines );
00744 rootmachines.clear();
00745 return ret;
00746 }
00747 catch( const parser_error<std::string, iter_t>& e )
00748 {
00749
00750
00751 clear();
00752 throw file_parse_exception(
00753 new parse_exception_syntactic_error( e.descriptor ),
00754 mpositer.get_position().file, mpositer.get_position().line,
00755 mpositer.get_position().column );
00756 }
00757 catch( const parser_error<GraphSyntaxErrors, iter_t>& )
00758 {
00759
00760
00761 clear();
00762 throw file_parse_exception(
00763 new parse_exception_syntactic_error( "Expected one of: entry, handle, exit, transitions" ),
00764 mpositer.get_position().file, mpositer.get_position().line,
00765 mpositer.get_position().column );
00766 }
00767 catch( const parse_exception& e )
00768 {
00769
00770
00771 clear();
00772 throw file_parse_exception(
00773 e.copy(), mpositer.get_position().file,
00774 mpositer.get_position().line, mpositer.get_position().column );
00775 }
00776
00777
00778
00779 }
00780
00781 StateGraphParser::~StateGraphParser() {
00782 clear();
00783 delete valuechangeparser;
00784 delete expressionparser;
00785 delete conditionparser;
00786 delete peerparser;
00787 }
00788
00789 void StateGraphParser::clear() {
00790
00791
00792 valuechangeparser->reset();
00793
00794
00795
00796 commonparser->skipeol = true;
00797 selectln = 0;
00798 transProgram.reset();
00799 elseProgram.reset();
00800 delete argsparser;
00801 argsparser = 0;
00802 delete curcondition;
00803 curcondition = 0;
00804
00805 curstate = 0;
00806 delete curnonprecstate;
00807 curnonprecstate = 0;
00808
00809 curmachinebuilder = 0;
00810 curinstantiatedmachine.reset();
00811
00812 if ( curtemplate )
00813 {
00814
00815
00816 for( StateMachine::ChildList::const_iterator it= curtemplate->getChildren().begin();
00817 it != curtemplate->getChildren().end(); ++it ) {
00818 ParsedStateMachine* psc = dynamic_cast<ParsedStateMachine*>( it->get() );
00819 if (psc && psc->getService() ) {
00820 context->provides()->removeService( psc->getService()->getName() );
00821 }
00822 }
00823
00824 curtemplate->getService()->clear();
00825
00826
00827 curtemplate.reset();
00828 }
00829
00830 for ( std::vector<ActionInterface*>::iterator i = varinitcommands.begin();
00831 i != varinitcommands.end(); ++ i )
00832 delete *i;
00833 varinitcommands.clear();
00834 for ( std::vector<ActionInterface*>::iterator i = paraminitcommands.begin();
00835 i != paraminitcommands.end(); ++ i )
00836 delete *i;
00837 paraminitcommands.clear();
00838 for ( machinebuilders_t::iterator i = machinebuilders.begin();
00839 i != machinebuilders.end(); ++i )
00840 delete i->second;
00841 machinebuilders.clear();
00842
00843 }
00844
00845 void StateGraphParser::seenstatemachinename( iter_t begin, iter_t end ) {
00846
00847 curmachinename = std::string ( begin, end );
00848
00849
00850 if ( machinebuilders.count( curmachinename ) != 0 )
00851 ORO_THROW( parse_exception_semantic_error("StateMachine type " + curmachinename + " redefined."));
00852
00853 curtemplate.reset(new ParsedStateMachine());
00854
00855
00856 curobject.reset( new StateMachineService(curtemplate, context ) );
00857 curobject->setName( curmachinename );
00858 curtemplate->setService( curobject );
00859
00860
00861
00862 progParser = new ProgramGraphParser(mpositer, context, caller, *commonparser);
00863
00864
00865 curtemplate->setName( curmachinename, false );
00866 }
00867
00868 void StateGraphParser::storeOffset() {
00869
00870
00871 ln_offset = mpositer.get_position().line - 1;
00872
00873 saveStartPos = mpositer;
00874 }
00875
00876 void StateGraphParser::saveText( iter_t begin, iter_t end ) {
00877 assert( curmachinename.length() != 0 );
00878
00879 if ( machinebuilders.count( curmachinename ) == 0 )
00880 return;
00881
00882 machinebuilders[curmachinename]->item()->setText( std::string( saveStartPos, end) );
00883 this->storeOffset();
00884 }
00885
00886 void StateGraphParser::inpreconditions() {
00887
00888 assert( curnonprecstate == 0 );
00889 curnonprecstate = curstate->postponeState();
00890
00891 curtemplate->addState( curnonprecstate );
00892 }
00893
00894 void StateGraphParser::seenpreconditions() {
00895 curtemplate->transitionSet( curstate, curnonprecstate, new ConditionTrue, rank--, mpositer.get_position().line - ln_offset );
00896 curstate->setDefined( true );
00897 curstate = curnonprecstate;
00898 curnonprecstate = 0;
00899 }
00900
00901 void StateGraphParser::startrootmachineinstantiation() {
00902 isroot = true;
00903 }
00904
00905 void StateGraphParser::seenrootmachineinstantiation() {
00906
00907 isroot = false;
00908 if( rootmachines.find( curinstmachinename ) != rootmachines.end() )
00909 ORO_THROW( parse_exception_semantic_error( "Root machine \"" + curinstmachinename + "\" already defined." ));
00910 rootmachines[curinstmachinename] = curinstantiatedmachine;
00911
00912
00913
00914 curinstantiatedmachine->setName( curinstmachinename, true );
00915
00916
00917 if ( context->provides()->hasService( curinstmachinename ) )
00918 ORO_THROW( parse_exception_semantic_error("TaskContext '"+context->getName()+"' has already a Service named '" + curinstmachinename + "' ."));
00919
00920
00921 context->provides()->addService( curinstantiatedmachine->getService() );
00922
00923 curinstantiatedmachine.reset();
00924 curinstmachinename.clear();
00925 }
00926
00927 void StateGraphParser::seensubMachineinstantiation() {
00928 if ( find_if( curtemplate->getChildren().begin(),
00929 curtemplate->getChildren().end(),
00930 boost::bind( equal_to<string>(), boost::bind(&StateMachine::getName,_1), curinstmachinename )) != curtemplate->getChildren().end() )
00931 ORO_THROW( parse_exception_semantic_error( "SubMachine \"" + curinstmachinename + "\" already defined." ));
00932
00933
00934
00935
00936
00937
00938 if ( !context->provides()->addService( curinstantiatedmachine->getService() ) )
00939 ORO_THROW( parse_exception_semantic_error(
00940 "Name clash: name of instantiated machine \"" + curinstmachinename +
00941 "\" already used as object name in task '"+context->getName()+"'." ));
00942
00943
00944 curtemplate->addChild( curinstantiatedmachine );
00945
00946 curtemplate->getService()->addService( curinstantiatedmachine->getService() );
00947
00948 curinstantiatedmachine->setName(curinstmachinename, false );
00949
00950 curinstantiatedmachine.reset();
00951 curinstmachinename.clear();
00952 }
00953
00954 void StateGraphParser::seenmachinetypename( iter_t begin, iter_t end ) {
00955 assert( curmachinebuilder == 0 );
00956 std::string name( begin, end );
00957 machinebuilders_t::iterator i = machinebuilders.find( name );
00958 if ( i == machinebuilders.end() )
00959 ORO_THROW( parse_exception_semantic_error( "StateMachine \"" + name + "\" not defined." ));
00960 curmachinebuilder = i->second;
00961 }
00962
00963 void StateGraphParser::seeninstmachinename( iter_t begin, iter_t end ) {
00964 assert( curmachinebuilder != 0 );
00965 assert( curinstmachinename.empty() );
00966 curinstmachinename = std::string( begin, end );
00967 }
00968
00969 void StateGraphParser::seenmachineinstargumentname( iter_t begin, iter_t end ) {
00970 assert( curmachineinstargumentname.empty() );
00971 std::string name( begin, end );
00972 curmachineinstargumentname = name;
00973 }
00974
00975 void StateGraphParser::seenmachineinstargumentvalue() {
00976 DataSourceBase::shared_ptr value = expressionparser->getResult();
00977
00978 expressionparser->dropResult();
00979 if ( curinstmachineparams.find( curmachineinstargumentname ) != curinstmachineparams.end() )
00980 ORO_THROW( parse_exception_semantic_error(
00981 "In initialisation of StateMachine \"" + curinstmachinename +
00982 "\": Parameter \"" + curmachineinstargumentname +"\" initialised twice..." ));
00983 curinstmachineparams[curmachineinstargumentname] = value;
00984 curmachineinstargumentname.clear();
00985 }
00986
00987 void StateGraphParser::seenmachineinstantiation()
00988 {
00989
00990
00991
00992
00993
00994
00995 ParsedStateMachinePtr nsc( curmachinebuilder->build( isroot ) );
00996
00997
00998
00999 machineparams_t params = nsc->getParameters();
01000
01001
01002
01003 for ( machineparamvalues_t::iterator i = curinstmachineparams.begin(); i != curinstmachineparams.end(); ++i )
01004 {
01005 machineparams_t::iterator j = params.find( i->first );
01006 if ( j == params.end() )
01007 ORO_THROW( parse_exception_semantic_error( "No parameter \"" + i->first + "\" in this StateMachine." ) );
01008 }
01009
01010 for ( machineparams_t::iterator i = params.begin(); i != params.end(); ++i )
01011 {
01012 machineparamvalues_t::iterator j = curinstmachineparams.find( i->first );
01013 if ( j == curinstmachineparams.end() )
01014 ORO_THROW( parse_exception_semantic_error(
01015 "No value given for argument \"" + i->first + "\" in instantiation of this StateMachine." ));
01016 #ifndef ORO_EMBEDDED
01017 try {
01018 paraminitcommands.push_back( i->second->getDataSource()->updateAction( j->second.get() ) );
01019 }
01020 catch( const bad_assignment& )
01021 {
01022 throw parse_exception_semantic_error("Attempt to initialize parameter '"+i->first+"' with a value which is of a different type." );
01023 }
01024 #else
01025 ActionInterface* ret = i->second->getDataSource()->updateAction( j->second.get());
01026 if (ret)
01027 paraminitcommands.push_back( ret );
01028 else
01029 return;
01030 #endif
01031 }
01032
01033 curinstantiatedmachine = nsc;
01034
01035
01036
01037 if ( paraminitcommands.size() > 0 )
01038 {
01039 CommandComposite* comcom = new CommandComposite;
01040 for ( std::vector<ActionInterface*>::iterator i = paraminitcommands.begin();
01041 i != paraminitcommands.end(); ++i )
01042 comcom->add( *i );
01043
01044 if ( curinstantiatedmachine->getInitCommand() )
01045 comcom->add( curinstantiatedmachine->getInitCommand() );
01046 curinstantiatedmachine->setInitCommand( comcom );
01047 }
01048 paraminitcommands.clear();
01049
01050 curmachinebuilder = 0;
01051 curinstmachineparams.clear();
01052
01053
01054 curinstantiatedmachine->getService()->setName(curinstmachinename );
01055 }
01056
01057 void StateGraphParser::seenmachinevariable() {
01058 std::vector<ActionInterface*> acv = valuechangeparser->assignCommands();
01059 for(std::vector<ActionInterface*>::iterator it = acv.begin(); it!=acv.end(); ++it)
01060 varinitcommands.push_back( *it );
01061
01062 valuechangeparser->clear();
01063 }
01064
01065 void StateGraphParser::seenmachineparam() {
01066 std::vector<std::string> pnames = valuechangeparser->definedNames();
01067 std::vector<AttributeBase*> tbases = valuechangeparser->definedValues();
01068 assert( pnames.size() == tbases.size() );
01069 for (unsigned int i = 0; i < pnames.size(); ++i)
01070 curtemplate->addParameter( pnames[i] , tbases[i] );
01071
01072 valuechangeparser->clear();
01073 }
01074
01075
01076 }