Turnstile.cpp
Go to the documentation of this file.
00001 
00002 #include <iostream>
00003 
00004 #include <ros/ros.h>
00005 
00006 #include <decision_making/SynchCout.h>
00007 #include <decision_making/BT.h>
00008 #include <decision_making/FSM.h>
00009 #include <decision_making/ROSTask.h>
00010 #include <decision_making/DecisionMaking.h>
00011 
00012 using namespace std;
00013 using namespace decision_making;
00014 
00015 FSM(Turnstile)
00016 {
00017         FSM_STATES
00018         {
00019                 Locked,
00020                 Unlocked
00021         }
00022         FSM_START(Locked);
00023         FSM_BGN
00024         {
00025                 FSM_STATE(Locked)
00026                 {
00027                         FSM_TRANSITIONS
00028                         {
00029                                 FSM_ON_EVENT("/COIN", FSM_NEXT(Unlocked));
00030                                 FSM_ON_EVENT("/PUSH", FSM_NEXT(Locked));
00031                         }
00032                 }
00033                 FSM_STATE(Unlocked)
00034                 {
00035                         FSM_TRANSITIONS
00036                         {
00037                                 FSM_ON_EVENT("/COIN", FSM_NEXT(Unlocked));
00038                                 FSM_ON_EVENT("/PUSH", FSM_NEXT(Locked));
00039                         }
00040                 }
00041         }
00042         FSM_END
00043 }
00044 
00045 int main(int argc, char** argv){
00046 
00047         ros::init(argc, argv, "fsm_turnstile");
00048         ros_decision_making_init(argc, argv);
00049 
00050         ros::AsyncSpinner spinner(2);
00051         spinner.start();
00052 
00053         ROS_INFO("Starting turnstile...");
00054         FsmTurnstile(NULL, new RosEventQueue());
00055 
00056         spinner.stop();
00057 
00058         return 0;
00059 }
00060 
00061 


decision_making_examples
Author(s):
autogenerated on Wed Aug 26 2015 11:17:01