HybridExample.cpp
Go to the documentation of this file.
00001 
00002 #include <iostream>
00003 
00004 
00005 #include <boost/thread.hpp>
00006 #include <deque>
00007 #include <vector>
00008 #include <boost/thread/mutex.hpp>
00009 #include <boost/thread/condition.hpp>
00010 #include <boost/shared_ptr.hpp>
00011 
00012 
00013 using namespace std;
00014 
00015 #include <SynchCout.h>
00016 #include <EventSystem.h>
00017 
00018 using namespace decision_making;
00019 
00020 
00021 EventQueue mainEventQueue;
00022 
00023 
00024 void EVENTS_GENERATOR(){
00025 //      Event spec[]={"SUCCESS", "FAIL", "SUCCESS", "FAIL", "SUCCESS", "FAIL", "SUCCESS", "FAIL", "GO", "NOTHING"};
00026 //      Event spec[]={"FAIL", "NOTHING"};
00027         Event spec[]={"SUCCESS","SUCCESS","SUCCESS","SUCCESS","SUCCESS","SUCCESS","GO", "NOTHING"};
00028         int i=0;
00029         boost::this_thread::sleep(boost::posix_time::seconds(1));
00030         while(true){
00031                 Event t = spec[i];
00032                 if(t == "NOTHING"){ i=1; t=spec[0]; }else i++;
00033                 cout << endl << t<<" -> ";
00034                 mainEventQueue.riseEvent(t);
00035                 boost::this_thread::sleep(boost::posix_time::seconds(2));
00036         }
00037 }
00038 
00039 
00040 //==================== END OF SYMULATION OF REAL SYSTEM ======================
00041 
00042 #define X(x) x
00043 #define PAUSE boost::this_thread::sleep(boost::posix_time::seconds(1.3));
00044 #define TIMES(N) for(size_t times=0;times<N;times++)
00045 
00046 #include "BT.h"
00047 #include "FSM.h"
00048 
00049 
00050 //==================== CONNECTION TO REAL TASKS ==============================
00051 
00052 
00053 TaskResult callTask(std::string task_address, const CallContext& call_ctx, EventQueue& queue){
00054         DMDEBUG( cout<<" TASK("<<task_address<<":CALL) " ;)
00055         while(true)
00056         {
00057                 Event e = queue.waitEvent();
00058                 if(not e){
00059                         DMDEBUG( cout<<" TASK("<<task_address<<":TERMINATED) " ; )
00060                         return TaskResult::TERMINATED();
00061                 }
00062                 if( e=="/SUCCESS" or e=="/FAIL" or e=="/GO" ){
00063                         Event new_event ( Event(""+e.event_name(), call_ctx) );
00064                         DMDEBUG( cout<<" TASK("<<task_address<<":"<<new_event<<") "; )
00065                         queue.riseEvent(new_event);
00066                 }
00067 
00068                 if(e=="/GO" and task_address=="T3") return TaskResult::SUCCESS();
00069                 //return TaskResult::FAIL();
00070         }
00071         return TaskResult::FAIL();
00072 }
00073 
00074 #define CALL_REMOTE(NAME, CALLS, EVENTS) boost::bind(&callTask, #NAME, CALLS, EVENTS)
00075 
00076 
00077 #include "DecisionMaking.h"
00078 
00079 //=============================================================================
00080 
00081 
00082 FSM(TEST1){
00083         enum STATt{
00084                 C,
00085                 D,
00086                 S
00087         }
00088         FSM_START(C);
00089         FSM_BGN{
00090                 FSM_STATE( C ){
00091                         FSM_CALL_TASK(C);
00092                         FSM_TRANSITIONS{
00093                                 FSM_ON_EVENT(C/SUCCESS, FSM_NEXT(D));
00094                                 FSM_ON_EVENT(C/FAIL, FSM_NEXT(D));
00095                         }
00096                 }
00097                 FSM_STATE( D ){
00098                         FSM_CALL_TASK(D);
00099                         FSM_TRANSITIONS{
00100 //                              FSM_ON_EVENT(D/SUCCESS, FSM_NEXT(D));
00101 //                              FSM_ON_EVENT(D/FAIL, FSM_NEXT(D));
00102                         }
00103                 }
00104                 FSM_STATE( S ){
00105                         FSM_STOP(SUCCESS, TaskResult::SUCCESS());
00106                         FSM_TRANSITIONS{}
00107                 }
00108         }
00109         FSM_END
00110 }
00111 
00112 
00113 BT_BGN(BT1){
00114         BT_PAR_BGN(P1){
00115                 BT_CALL_TASK(T1);
00116                 BT_CALL_TASK(T2);
00117         }
00118         BT_PAR_END(P1);
00119 }
00120 BT_END(BT1);
00121 
00122 
00123 //struct _bt_function_struct{
00124 //TaskResult _bt_function(std::string task_address, CallContext& call_ctx, EventQueue& queue){
00125 //      BTContext _tmp_context;
00126 //      BT_ROOT_BGN(bt_from_fsm, __tmp_event_queue()){
00127 //              call_ctx.pop();
00128 //              BT_PAR_BGN(TMP){
00129 //                      call_ctx.pop();
00130 //                      BT_TASK_BGN(STOP_CONDITION){
00131 //                              while(not isTerminated())
00132 //                              {
00133 //                                      Event e = events.waitEvent();
00134 //                                      if(not e){
00135 //                                              cout<<" (STOP_CONDITION:TERMINATED) ";
00136 //                                              BT_TASK_RESULT( TaskResult::TERMINATED() );
00137 //                                              break;
00138 //                                      }
00139 //                              }
00140 //                      }
00141 //                      BT_TASK_END(STOP_CONDITION);
00142 //                      BT_CALL_BT(BT1);
00143 //              }
00144 //              BT_PAR_END(TMP);
00145 //      }
00146 //      BT_END(bt_from_fsm) bt_from_fsm(_tmp_context, call_ctx, queue);
00147 //      TaskResult res = bt_from_fsm.run();
00148 //      cout<<"(fsm from function finished)";
00149 //      return res;
00150 //}
00151 //} _bt_function_struct_instance;
00152 //#define CALL_BT_FUNCTION(NAME, CALLS, EVENTS) boost::bind(&_bt_function_struct::_bt_function, &_bt_function_struct_instance, #NAME, CALLS, EVENTS)
00153 
00154 
00155 
00156 
00157 //X(
00158 FSM(TEST){
00159         enum STATt{
00160                 A,
00161                 B,
00162                 STOP
00163         }
00164         FSM_START(A);
00165         FSM_BGN{
00166                 FSM_STATE( A ){
00167                         FSM_CALL_TASK(TA);
00168                         //FSM_CALL_TASK(TB);
00169                         FSM_CALL_BT(BT1);
00170 
00171 
00172                         //FSM_RISE(GO_TO_STOP)
00173                         FSM_TRANSITIONS{
00174                                 FSM_PRINT_EVENT;
00175                                 FSM_ON_EVENT(TA/GO, FSM_NEXT(STOP));
00176                                 //FSM_ON_EVENT(/A/SUCCESS, FSM_NEXT(B));
00177                                 //FSM_ON_EVENT(/A/FAIL, FSM_NEXT(B));//
00178                                 //FSM_ON_EVENT(GO_TO_STOP, FSM_NEXT(STOP));
00179                         }
00180                 }
00181                 FSM_STATE( B ){
00182                         FSM_CALL_FSM(TEST1);
00183                         FSM_TRANSITIONS{
00184                                 FSM_PRINT_EVENT;
00185                                 FSM_ON_EVENT(TEST1/D/SUCCESS, FSM_NEXT(A));
00186                                 //FSM_ON_EVENT(FAIL, FSM_NEXT(B));
00187                         }
00188                 }
00189                 FSM_STATE( STOP ){
00190 
00191                         FSM_TRANSITIONS
00192                 }
00193         }
00194         FSM_END
00195 }
00196 
00197 void FSM_TEST(){
00198         FsmTEST(NULL,&mainEventQueue);
00199 }
00200 
00201 TaskResult BT_run_(){
00202         BT_ROOT_BGN(root, mainEventQueue){
00203                 BT_PAR_BGN(P1){
00204 //                      BT_TASK_BGN(MY1){
00205 //                              cout<<"HELLO"<<endl;
00206 //                              FSM_TEST();
00207 //                              BT_TASK_RESULT( TaskResult::SUCCESS() );
00208 //                      }
00209 //                      BT_TASK_END(MY1);
00210                         BT_CALL_FSM(TEST);
00211 
00212 //                      BT_SEQ_BGN(S1){
00213 //                              BT_TASK_ROS(T1);
00214 //                              BT_TASK_ROS(T2);
00215 //                      }
00216 //                      BT_SEQ_END(S1);
00217                         BT_CALL_TASK(T3);
00218                         BT_CALL_TASK(T4);
00219                         BT_CALL_BT(BT1);
00220                 }
00221                 BT_PAR_END(P1);
00222         }
00223         BT_END(root) main;
00224         return main.run();
00225 }
00226 
00227 
00228 int main() {
00229 
00230 boost::thread_group threads;
00231 threads.add_thread(new boost::thread(boost::bind(&BT_run_)));
00232 //threads.add_thread(new boost::thread(boost::bind(&FSM_TEST)));
00233 threads.add_thread(new boost::thread(boost::bind(&EVENTS_GENERATOR)));
00234 
00235 threads.join_all();
00236 
00237 return 0;
00238 }
00239 
00240 
00241 


decision_making
Author(s):
autogenerated on Wed Aug 26 2015 11:16:53