Go to the documentation of this file.00001 #include "tour_manager.h"
00002 #include "bwi_virtour/RequestTour.h"
00003 #include "bwi_virtour/PingTour.h"
00004 #include "bwi_virtour/GetTourState.h"
00005 #include "bwi_virtour/LeaveTour.h"
00006 #include "bwi_virtour/Authenticate.h"
00007
00008 TourManager* tm;
00009
00010 bool requestTour(bwi_virtour::RequestTour::Request &req,
00011 bwi_virtour::RequestTour::Response &res) {
00012
00013 if (tm->tourAllowed) {
00014 if (!tm->tourInProgress) {
00015
00016 tm->tourLeader = req.user;
00017 tm->tourInProgress = true;
00018 tm->tourStartTime = ros::Time::now();
00019 tm->lastPingTime = ros::Time::now();
00020 res.startTime = tm->tourStartTime.toSec();
00021 res.result = tm->tourDuration;
00022 ROS_INFO("New tour leader is %s", req.user.c_str());
00023 } else if (ros::Time::now() - tm->lastPingTime > ros::Duration(30)) {
00024
00025 tm->tourLeader = req.user;
00026 tm->tourInProgress = true;
00027 tm->tourStartTime = ros::Time::now();
00028 tm->lastPingTime = ros::Time::now();
00029 res.startTime = tm->tourStartTime.toSec();
00030 res.result = tm->tourDuration;
00031 ROS_INFO("Last tour expired! New tour leader is %s", req.user.c_str());
00032 } else {
00033 res.result = TourManager::ERROR_TOURINPROGRESS;
00034 }
00035 } else {
00036 res.result = TourManager::ERROR_NOTOURALLOWED;
00037 }
00038
00039 return true;
00040 }
00041
00042 void checkTourExpired() {
00043 ros::Duration d = ros::Time::now() - tm->lastPingTime;
00044 if (tm->tourAllowed && tm->tourInProgress &&
00045 ros::Time::now() - tm->lastPingTime > ros::Duration(30)) {
00046 tm->tourInProgress = false;
00047 tm->tourLeader = "";
00048 ROS_INFO("Tour expired!");
00049 }
00050 }
00051
00052 bool pingTour(bwi_virtour::PingTour::Request &req,
00053 bwi_virtour::PingTour::Response &res) {
00054
00055 if (tm->tourAllowed) {
00056 if (tm->tourInProgress) {
00057 if (req.user.compare(tm->tourLeader) == 0) {
00058 tm->lastPingTime = ros::Time::now();
00059 res.result = 1;
00060 } else {
00061 res.result = TourManager::ERROR_NOTTOURLEADER;
00062 }
00063 } else {
00064 res.result = TourManager::ERROR_NOTOURINPROGRESS;
00065 }
00066 } else {
00067 res.result = TourManager::ERROR_NOTOURALLOWED;
00068 }
00069 return true;
00070 }
00071
00072 bool getTourState(bwi_virtour::GetTourState::Request &req,
00073 bwi_virtour::GetTourState::Response &res) {
00074
00075 checkTourExpired();
00076
00077 res.tourAllowed = tm->tourAllowed;
00078 res.tourInProgress = tm->tourInProgress;
00079 res.tourDuration = tm->tourDuration;
00080 res.tourStartTime = tm->tourStartTime.toSec();
00081 res.lastPingTime = tm->lastPingTime.toSec();
00082 res.tourLeader = "";
00083
00084
00085 return true;
00086 }
00087
00088 bool leaveTour(bwi_virtour::LeaveTour::Request &req,
00089 bwi_virtour::LeaveTour::Response &res) {
00090
00091 if (tm->tourInProgress && req.user.compare(tm->tourLeader) == 0) {
00092
00093 tm->tourInProgress = false;
00094 tm->tourLeader = "";
00095 ROS_INFO("%s left the tour!", req.user.c_str());
00096
00097 res.result = 1;
00098 } else {
00099 res.result = TourManager::ERROR_NOTTOURLEADER;
00100 }
00101
00102 return true;
00103 }
00104
00105 bool authenticate(bwi_virtour::Authenticate::Request &req,
00106 bwi_virtour::Authenticate::Response &res) {
00107
00108 if (tm->tourAllowed) {
00109 if (tm->tourInProgress) {
00110 if (req.user.compare(tm->tourLeader) == 0) {
00111 res.result = 1;
00112 } else {
00113 res.result = TourManager::ERROR_NOTTOURLEADER;
00114 }
00115 } else {
00116 res.result = TourManager::ERROR_NOTOURINPROGRESS;
00117 }
00118 } else {
00119 res.result = TourManager::ERROR_NOTOURALLOWED;
00120 }
00121
00122 return true;
00123 }
00124
00125 int main(int argc, char **argv){
00126 ros::init(argc, argv, "tour_manager");
00127 ros::NodeHandle n;
00128
00129
00130 bool tour_enabled;
00131 n.param("/tour_manager/tour_enabled", tour_enabled, false);
00132 tm = new TourManager(tour_enabled);
00133
00134 ROS_INFO("Starting tour manager. Tours enabled: %s", tour_enabled ? "true" : "false");
00135
00136
00137 ros::ServiceServer request_service = n.advertiseService("tour_manager/request_tour", requestTour);
00138 ros::ServiceServer ping_service = n.advertiseService("tour_manager/ping_tour", pingTour);
00139 ros::ServiceServer get_tour_state_service = n.advertiseService("tour_manager/get_tour_state", getTourState);
00140 ros::ServiceServer leave_service = n.advertiseService("tour_manager/leave_tour", leaveTour);
00141 ros::ServiceServer authenticate_service = n.advertiseService("tour_manager/authenticate", authenticate);
00142
00143 ros::spin();
00144 return 0;
00145 }