Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 
00039 
00040 #include  <wgtest_status_indicator/delcom_usb_light.h>
00041 
00042 #include <ros/ros.h>
00043 #include <string>
00044 #include <signal.h>
00045 
00046 #include <pr2_self_test_msgs/TestInfoArray.h>
00047 
00048 using namespace wgtest_status_indicator;
00049 
00050 DelcomUSBLight *g_light;
00051 
00052 ros::Time *g_last_callback;
00053 
00054 volatile bool g_shutdown_req_;
00055 
00056 void signal_handler(int sig)
00057 {
00058   ROS_INFO("Caught signal, shutting down.");
00059   g_shutdown_req_ = true;
00060 }
00061 
00062 void callback(const pr2_self_test_msgs::TestInfoArray &msg)
00063 {
00064   int status = 0;
00065   for (unsigned int i = 0; i < msg.data.size(); ++i)
00066   {
00067     
00068     if (msg.data[i].test_status > 4)
00069       continue; 
00070 
00071     status = std::max(status, (int) msg.data[i].test_status);
00072   }
00073   
00074   
00075   USBLightCommand cmd;
00076   if (status == 0) 
00077     cmd.green = true;
00078   else if (status == 1) 
00079     cmd.orange = true;
00080   else 
00081     cmd.red = true;
00082 
00083   g_light->sendCommand(cmd);
00084 
00085   if (g_last_callback)
00086     delete g_last_callback;
00087   g_last_callback = new ros::Time(ros::Time::now());
00088 }
00089 
00090 
00091 void runNode()
00092 {
00093   ros::NodeHandle nh;
00094 
00095   ros::Subscriber stat_sub = nh.subscribe("test_info", 5, &callback);
00096 
00097   USBLightCommand red_cmd;
00098   red_cmd.red = true;
00099 
00100   ros::Rate my_rate(1.0);
00101   while (ros::ok() && !g_shutdown_req_)
00102   {
00103     ros::spinOnce();
00104     my_rate.sleep();
00105 
00106     
00107     if (ros::Time::now() - *g_last_callback > ros::Duration(30.0))
00108       g_light->sendCommand(red_cmd);
00109 
00110     if (!ros::master::check())
00111     {
00112       ROS_ERROR("ROS Master is down. Shutting down ROS.");
00113       break;
00114     }
00115   }
00116 
00117   
00118   g_light->sendCommand(red_cmd);
00119 
00120   ros::shutdown();
00121 }
00122 
00123 int main(int argc, char **argv)
00124 {
00125   g_shutdown_req_ = false;
00126   g_last_callback = new ros::Time(0);
00127   g_light = new DelcomUSBLight();
00128 
00129   signal(SIGINT, signal_handler);
00130 
00131   ros::init(argc, argv, "wgtest_status_indicator", 
00132             ros::init_options::NoSigintHandler | ros::init_options::AnonymousName);
00133   ros::Time::init();
00134 
00135   USBLightCommand red_cmd;
00136   red_cmd.red = true;
00137   g_light->sendCommand(red_cmd);
00138 
00139   ros::WallRate wrate(1.0);
00140 
00141   while (!g_shutdown_req_)
00142   {
00143     wrate.sleep();
00144 
00145     if (!ros::master::check())
00146     {
00147       ROS_ERROR_THROTTLE(60, "Unable to contact master. Will retry");
00148       continue;
00149     }
00150 
00151     ROS_INFO("Main loop");
00152 
00153     
00154     runNode();
00155   }
00156 
00157   USBLightCommand off_cmd;
00158   off_cmd.off = true;
00159   g_light->sendCommand(off_cmd);
00160 
00161   delete g_light;
00162   delete g_last_callback;
00163 }