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 
00047 
00048 //==================== CONNECTION TO REAL TASKS ==============================
00049 
00050 
00051 #include "custom_decision_making.h"
00052 
00053 
00054 //=============================================================================
00055 
00056 
00057 #include "BT_BT1.h"
00058 #include "FSM_TEST.h"
00059 
00060 void FSM_TEST(){
00061         FsmTEST(NULL,&mainEventQueue);
00062 }
00063 
00064 TaskResult BT_run_(){
00065         BT_ROOT_BGN(root, mainEventQueue){
00066                 BT_PAR_BGN(P1){
00067 //                      BT_TASK_BGN(MY1){
00068 //                              cout<<"HELLO"<<endl;
00069 //                              FSM_TEST();
00070 //                              BT_TASK_RESULT( TaskResult::SUCCESS() );
00071 //                      }
00072 //                      BT_TASK_END(MY1);
00073                         BT_CALL_FSM(TEST);
00074 
00075 //                      BT_SEQ_BGN(S1){
00076 //                              BT_TASK_ROS(T1);
00077 //                              BT_TASK_ROS(T2);
00078 //                      }
00079 //                      BT_SEQ_END(S1);
00080                         BT_CALL_TASK(T3);
00081                         BT_CALL_TASK(T4);
00082                         BT_CALL_BT(BT1);
00083                 }
00084                 BT_PAR_END(P1);
00085         }
00086         BT_END(root) main;
00087         return main.run();
00088 }
00089 
00090 
00091 int main() {
00092 
00093 boost::thread_group threads;
00094 threads.add_thread(new boost::thread(boost::bind(&BT_run_)));
00095 //threads.add_thread(new boost::thread(boost::bind(&FSM_TEST)));
00096 threads.add_thread(new boost::thread(boost::bind(&EVENTS_GENERATOR)));
00097 
00098 threads.join_all();
00099 
00100 return 0;
00101 }
00102 
00103 
00104 


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