ntp_monitor.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2008, 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 import roslib
00035 roslib.load_manifest('pr2_computer_monitor')
00036 
00037 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
00038 
00039 import sys
00040 import rospy
00041 import socket
00042 from subprocess import Popen, PIPE
00043 
00044 import time
00045 
00046 import re
00047 
00048 ##### monkey-patch to suppress threading error message in python 2.7.3
00049 ##### See http://stackoverflow.com/questions/13193278/understand-python-threading-bug
00050 if sys.version_info[:3] == (2, 7, 3):
00051     import threading
00052     threading._DummyThread._Thread__stop = lambda x: 42
00053 #####
00054 
00055 NAME = 'ntp_monitor'
00056 
00057 def ntp_monitor(ntp_hostname, offset=500, self_offset=500, diag_hostname = None, error_offset = 5000000):
00058     pub = rospy.Publisher("/diagnostics", DiagnosticArray)
00059     rospy.init_node(NAME, anonymous=True)
00060     
00061     hostname = socket.gethostname()
00062     if diag_hostname is None:
00063         diag_hostname = hostname
00064 
00065     stat = DiagnosticStatus()
00066     stat.level = 0
00067     stat.name = "NTP offset from "+ diag_hostname + " to " + ntp_hostname
00068     stat.message = "OK"
00069     stat.hardware_id = hostname
00070     stat.values = []
00071 
00072     self_stat = DiagnosticStatus()
00073     self_stat.level = DiagnosticStatus.OK
00074     self_stat.name = "NTP self-offset for "+ diag_hostname
00075     self_stat.message = "OK"
00076     self_stat.hardware_id = hostname
00077     self_stat.values = []
00078     
00079     while not rospy.is_shutdown():
00080         for st,host,off in [(stat,ntp_hostname,offset), (self_stat, hostname,self_offset)]:
00081             try:
00082                 p = Popen(["ntpdate", "-q", host], stdout=PIPE, stdin=PIPE, stderr=PIPE)
00083                 res = p.wait()
00084                 (o,e) = p.communicate()
00085             except OSError, (errno, msg):
00086                 if errno == 4:
00087                     break #ctrl-c interrupt
00088                 else:
00089                     raise
00090             if (res == 0):
00091                 measured_offset = float(re.search("offset (.*),", o).group(1))*1000000
00092 
00093                 st.level = DiagnosticStatus.OK
00094                 st.message = "OK"
00095                 st.values = [ KeyValue("Offset (us)", str(measured_offset)),
00096                               KeyValue("Offset tolerance (us)", str(off)),
00097                               KeyValue("Offset tolerance (us) for Error", str(error_offset)) ]
00098             
00099                 if (abs(measured_offset) > off):
00100                     st.level = DiagnosticStatus.WARN
00101                     st.message = "NTP Offset Too High"
00102                 if (abs(measured_offset) > error_offset):
00103                     st.level = DiagnosticStatus.ERROR
00104                     st.message = "NTP Offset Too High"
00105                                 
00106             else:
00107                 st.level = DiagnosticStatus.ERROR
00108                 st.message = "Error Running ntpdate. Returned %d" % res
00109                 st.values = [ KeyValue("Offset (us)", "N/A"),
00110                               KeyValue("Offset tolerance (us)", str(off)),
00111                               KeyValue("Offset tolerance (us) for Error", str(error_offset)),
00112                               KeyValue("Output", o),
00113                               KeyValue("Errors", e) ]
00114 
00115 
00116         msg = DiagnosticArray()
00117         msg.header.stamp = rospy.get_rostime()
00118         msg.status = [stat, self_stat]
00119         pub.publish(msg)
00120         time.sleep(1)
00121 
00122 def ntp_monitor_main(argv=sys.argv):
00123     import optparse
00124     parser = optparse.OptionParser(usage="usage: ntp_monitor ntp-hostname []")
00125     parser.add_option("--offset-tolerance", dest="offset_tol",
00126                       action="store", default=500,
00127                       help="Offset from NTP host", metavar="OFFSET-TOL")
00128     parser.add_option("--error-offset-tolerance", dest="error_offset_tol",
00129                       action="store", default=5000000,
00130                       help="Offset from NTP host. Above this is error", metavar="OFFSET-TOL")
00131     parser.add_option("--self_offset-tolerance", dest="self_offset_tol", 
00132                       action="store", default=500,
00133                       help="Offset from self", metavar="SELF_OFFSET-TOL")
00134     parser.add_option("--diag-hostname", dest="diag_hostname",
00135                       help="Computer name in diagnostics output (ex: 'c1')",
00136                       metavar="DIAG_HOSTNAME",
00137                       action="store", default=None)
00138     options, args = parser.parse_args(rospy.myargv())
00139 
00140     if (len(args) != 2):
00141         parser.error("Invalid arguments. Must have HOSTNAME [args]. %s" % args)
00142 
00143 
00144     try:
00145         offset = int(options.offset_tol)
00146         self_offset = int(options.self_offset_tol)
00147         error_offset = int(options.error_offset_tol)
00148     except:
00149         parser.error("Offsets must be numbers")        
00150     
00151     ntp_monitor(args[1], offset, self_offset, options.diag_hostname, error_offset)
00152     
00153 
00154 if __name__ == "__main__":
00155     try:
00156         ntp_monitor_main(rospy.myargv())
00157     except KeyboardInterrupt: pass
00158     except SystemExit: pass
00159     except:
00160         import traceback
00161         traceback.print_exc()


pr2_computer_monitor
Author(s): Kevin Watts (watts@willowgarage.com)
autogenerated on Thu Sep 3 2015 11:31:16