wgtest_status_indicator.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Simple utility to control delcom USB light from command line
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     // Ignore tests that aren't launched
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   // Make command
00075   USBLightCommand cmd;
00076   if (status == 0) // OK
00077     cmd.green = true;
00078   else if (status == 1) // WARN
00079     cmd.orange = true;
00080   else // ERROR
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 // Runs ROS node and handles any ROS communication
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     // Send red if we haven't heard from Test Manager in a while
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   // Send red if we're shut down
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     // Run Node
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 }


wgtest_status_indicator
Author(s): Kevin Watts
autogenerated on Sat Dec 28 2013 17:57:04