## For instruction on writing tutorials ## http://www.ros.org/wiki/WritingTutorials #################################### ##FILL ME IN #################################### ## for a custom note with links: ## note = ## for the canned note of "This tutorial assumes that you have completed the previous tutorials:" just add the links ## note.0=[[decision_making/Tutorials/CogniTAO(C++)]] ## descriptive title for the tutorial ## title =Getting Started with TAO in C++ ## multi-line description to be displayed in search ## description = TAO, Think As One ## the next tutorial description (optional) ## next = ## links to next tutorial (optional) ## next.0.link= ## next.1.link= ## what level user is this tutorial for ## level=BeginnerCategory ## keywords = decision_making,TAO #################################### <> <> == Introduction == As described in [[decision_making/Tutorials/CogniTAO|CogniTAO BDI]], a number of components (Plans, Tasks, Allocations) are written and designed by the programmer, while complying with the TAO Plans and hierarchy model. Here we will demonstrate how to put the pieces together, and create your first TAO program using those components, in an easy-to-catch tutorial that will cover most of what you need to understand, in order to comprehend the easy usage of TAO. == Running the example == {{{ roslaunch decision_making_examples tao_increment.launch }}} == Components, Conditions And Code == This is taoIncrement.cpp - In the following code we demonstrate the TAO Incremental example (hold on - it looks like much - so we'll break it down to pieces in a moment...). {{{ #!cplusplus block=header #include #include #include #include #include #include #include #include #include using namespace std; using namespace decision_making; #define foreach BOOST_FOREACH TAO_HEADER(Even) TAO_HEADER(Odd) //#define TAO_STOP_CONDITION(X) TAO_STOP_CONDITION_AND_PRINT_EVENTS(X) struct WorldModel: public CallContextParameters{ int i; string str()const{ stringstream s; s<<"i="<() TAO(Incrementer) { TAO_PLANS{ Increment, } TAO_START_PLAN(Increment); TAO_BGN{ TAO_PLAN( Increment ){ TAO_START_CONDITION( WM.i < 100 ); TAO_ALLOCATE(AllocFirstReady){ TAO_SUBPLAN(Even); TAO_SUBPLAN(Odd); } TAO_STOP_CONDITION( false ); TAO_NEXT(NextFirstReady){ TAO_NEXT_PLAN(Increment); } } } TAO_END } TAO(Even) { TAO_PLANS{ Even, } TAO_START_PLAN(Even); TAO_BGN { TAO_PLAN( Even ){ TAO_START_CONDITION( WM.i%2 == 0 ); WM.i++; cout<<"Even : "< #include #include #include #include #include #include #include #include using namespace std; using namespace decision_making; #define foreach BOOST_FOREACH TAO_HEADER(Even) TAO_HEADER(Odd) }}} A definition of the context parameters for our world model, which will be used in our Incremental START conditions: {{{ #!cplusplus block=header struct WorldModel: public CallContextParameters{ int i; string str()const{ stringstream s; s<<"i="<() }}} And now for the interesting part.. This is where TAO really comes in - We define the TAO plans for each component (according to[[decision_making/Tutorials/CogniTAO(C++)|TAO C++ reference]] as follows: First for Incremental, our condition will be to run for 100 times (our context parameter will be incremented by our sub-plans). notice the NEXT is the Incremental plan again, and our sub-plans are Odd and Even. {{{ #!cplusplus block=header TAO(Incrementer) { TAO_PLANS{ Increment, } TAO_START_PLAN(Increment); TAO_BGN{ TAO_PLAN( Increment ){ TAO_START_CONDITION( WM.i < 100 ); TAO_ALLOCATE(AllocFirstReady){ TAO_SUBPLAN(Even); TAO_SUBPLAN(Odd); } TAO_STOP_CONDITION( false ); TAO_NEXT(NextFirstReady){ TAO_NEXT_PLAN(Increment); } } } TAO_END } }}} And now for Even and Odd - after our Start condition we'll increment the context parameter, notice these are the last plans, so they have no TAO_ALLOCATE and no TAO_NEXT, we use the _EMPTY option instead. Here we go: {{{ #!cplusplus block=header TAO(Even) { TAO_PLANS{ Even, } TAO_START_PLAN(Even); TAO_BGN { TAO_PLAN( Even ){ TAO_START_CONDITION( WM.i%2 == 0 ); WM.i++; cout<<"Even : "<