Go to the documentation of this file.00001
00002
00003
00004
00005 #include <rail_user_queue_manager/rail_user_queue_manager.h>
00006
00007 using namespace std;
00008 using namespace rail;
00009
00010 int main(int argc, char *argv[])
00011 {
00012 ros::init(argc, argv, "queue_manager");
00013
00014
00015 UserQueueManager queue_manager;
00016
00017 return EXIT_SUCCESS;
00018 }
00019
00020 UserQueueManager::UserQueueManager() : countdown_(DEFAULT_TRIAL), run_countdown_(false), private_node_("~")
00021 {
00022
00023 ros::Publisher queue_pub = private_node_.advertise<rail_user_queue_manager::Queue>("queue", 1000);
00024
00025 ros::ServiceServer update_queue_serv = private_node_.advertiseService("update_queue",
00026 &UserQueueManager::onUpdateQueue, this);
00027
00028
00029 ros::Rate r(LOOP_RATE);
00030
00031 ROS_INFO("publishing queue...");
00032
00033 while (ros::ok())
00034 {
00035
00036
00037
00038 if (run_countdown_)
00039 {
00040
00041 if (!countdown_)
00042 {
00043 queue_.pop_front();
00044
00045 countdown_ = queue_.begin()->second;
00046 }
00047
00048
00049 if (queue_.empty())
00050 {
00051 run_countdown_ = false;
00052 }
00053
00054 countdown_--;
00055 }
00056
00057 rail_user_queue_manager::Queue queue_message;
00058
00059 deque<pair<int, int> >::iterator it = queue_.begin();
00060 int position = 0;
00061 int wait_t;
00062 int t_left;
00063
00064
00065 while (it != queue_.end())
00066 {
00067 pair<int, int> user = *(it++);
00068
00069 rail_user_queue_manager::UserStatus user_status;
00070 user_status.user_id = user.first;
00071
00072
00073
00074 if (position > 0)
00075 {
00076 wait_t = countdown_ + (position - 1) * user.second;
00077 }
00078 else if (position == 0)
00079 {
00080 wait_t = -1;
00081 t_left = countdown_;
00082 }
00083
00084 ros::Duration wait_time(wait_t);
00085 ros::Duration time_left(t_left);
00086 user_status.wait_time = wait_time;
00087 user_status.time_left = time_left;
00088 queue_message.queue.push_back(user_status);
00089
00090 position++;
00091
00092
00093 }
00094
00095
00096 queue_pub.publish(queue_message);
00097
00098 ros::spinOnce();
00099 r.sleep();
00100 }
00101 }
00102
00103 bool UserQueueManager::onUpdateQueue(rail_user_queue_manager::UpdateQueue::Request &req,
00104 rail_user_queue_manager::UpdateQueue::Response &res)
00105 {
00106
00107 int user_id = req.user_id;
00108 int study_time = req.study_time;
00109
00110
00111 deque<pair<int, int> >::iterator it = queue_.begin();
00112 while (it != queue_.end())
00113 {
00114 if (user_id == (*it).first)
00115 {
00116 if (!req.enqueue)
00117 {
00118
00119 if (it == queue_.begin())
00120 {
00121 queue_.pop_front();
00122 int next_study_time = queue_.front().second;
00123 countdown_ = next_study_time ? next_study_time : DEFAULT_TRIAL;
00124 } else
00125 {
00126 queue_.erase(it);
00127 }
00128 }
00129 return true;
00130 }
00131 it++;
00132 }
00133
00134 if (req.enqueue)
00135 {
00136 study_time = study_time ? study_time : DEFAULT_TRIAL;
00137
00138
00139 queue_.push_back(pair<int, int>(user_id, study_time));
00140 countdown_ = study_time;
00141
00142
00143 run_countdown_ = true;
00144 }
00145 return true;
00146 }