TurnstileEvents.cpp
Go to the documentation of this file.
00001 /*
00002  * Filename: TurnstileEvents.cpp
00003  *   Author: Igor Makhtes
00004  *     Date: Jan 7, 2014
00005  *
00006  * The MIT License (MIT)
00007  *
00008  * Copyright (c) 2014 Cogniteam Ltd.
00009  *
00010  * Permission is hereby granted, free of charge, to any person obtaining a copy
00011  * of this software and associated documentation files (the "Software"), to deal
00012  * in the Software without restriction, including without limitation the rights
00013  * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
00014  * copies of the Software, and to permit persons to whom the Software is
00015  * furnished to do so, subject to the following conditions:
00016  *
00017  * The above copyright notice and this permission notice shall be included in
00018  * all copies or substantial portions of the Software.
00019  *
00020  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
00021  * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00022  * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
00023  * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
00024  * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
00025  * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
00026  * THE SOFTWARE.
00027  */
00028 
00029 #include <iostream>
00030 #include <boost/bind.hpp>
00031 #include <boost/thread.hpp>
00032 #include <boost/foreach.hpp>
00033 #include <boost/assign/std/vector.hpp>
00034 
00035 #include <ros/ros.h>
00036 #include <std_msgs/String.h>
00037 
00038 using namespace std;
00039 using namespace boost::assign;
00040 
00041 #define foreach BOOST_FOREACH
00042 
00043 
00044 int main(int argc, char **argv) {
00045     ros::init(argc, argv, "fsm_turstile_events");
00046 
00047     ros::NodeHandle node;
00048     ros::Publisher eventPublisher = node.advertise<std_msgs::String>("/decision_making/fsm_turnstile/events", 1, false);
00049 
00050     int currentEvent = 0;
00051     vector<string> events;
00052     events += "COIN","COIN","PUSH","PUSH";
00053 
00054     ROS_INFO("Starting turnstile event publisher...");
00055 
00056     while (ros::ok()) {
00057         std_msgs::String event;
00058         event.data = events[currentEvent++];
00059         currentEvent %= events.size();
00060 
00061         eventPublisher.publish(event);
00062         boost::this_thread::sleep(boost::posix_time::seconds(1));
00063     }
00064         return 0;
00065 }


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