ntp_monitor.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00004 #
00005 # Licensed under the Apache License, Version 2.0 (the "License");
00006 # you may not use this file except in compliance with the License.
00007 # You may obtain a copy of the License at
00008 #
00009 #   http://www.apache.org/licenses/LICENSE-2.0
00010 #
00011 # Unless required by applicable law or agreed to in writing, software
00012 # distributed under the License is distributed on an "AS IS" BASIS,
00013 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014 # See the License for the specific language governing permissions and
00015 # limitations under the License.
00016 
00017 from __future__ import print_function
00018 
00019 import sys
00020 import socket
00021 from subprocess import Popen, PIPE
00022 import time
00023 import re
00024 
00025 import rospy
00026 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
00027 
00028 class NtpMonitor():
00029     def __init__(self, argv=sys.argv):
00030         rospy.init_node("ntp_monitor")
00031         self.parse_args(argv)
00032 
00033         stat = DiagnosticStatus()
00034         stat.level = DiagnosticStatus.WARN
00035         stat.name = '%s NTP Offset' % self.diag_hostname
00036         stat.message = 'No Data'
00037         stat.hardware_id = self.diag_hostname
00038         stat.values = []
00039         self.msg = DiagnosticArray()
00040         self.msg.header.stamp = rospy.get_rostime()
00041         self.msg.status = [stat]
00042 
00043         self.update_diagnostics()
00044 
00045         self.diag_pub = rospy.Publisher("/diagnostics", DiagnosticArray, queue_size=1)
00046         self.diag_timer = rospy.Timer(rospy.Duration(1.0), self.publish_diagnostics)
00047         self.monitor_timer = rospy.Timer(rospy.Duration(60.0), self.update_diagnostics)
00048 
00049     def update_diagnostics(self, event=None):
00050         stat = DiagnosticStatus()
00051         stat.level = DiagnosticStatus.WARN
00052         stat.name = '%s NTP Offset' % self.diag_hostname
00053         stat.message = 'No Data'
00054         stat.hardware_id = self.diag_hostname
00055         stat.values = []
00056         
00057         try:
00058             for st,host,off in [(stat, self.ntp_server, self.offset)]:
00059                 p = Popen(["ntpdate", "-q", host], stdout=PIPE, stdin=PIPE, stderr=PIPE)
00060                 retcode = p.wait()
00061                 stdout, stderr = p.communicate()
00062 
00063                 if retcode != 0:
00064                     st.level = DiagnosticStatus.ERROR
00065                     st.message = 'ntpdate Error'
00066                     st.values = [ KeyValue(key = 'ntpdate Error', value = stderr),
00067                                   KeyValue(key = 'Output', value = stdout) ]
00068                     continue
00069 
00070                 measured_offset = float(re.search("offset (.*),", stdout).group(1))*1000000
00071 
00072                 st.level = DiagnosticStatus.OK
00073                 st.message = "OK"
00074                 st.values = [ KeyValue("NTP Server" , self.ntp_server),
00075                               KeyValue("Offset (us)", str(measured_offset)),
00076                               KeyValue("Offset tolerance (us)", str(off)),
00077                               KeyValue("Offset tolerance (us) for Error", str(self.error_offset)) ]
00078 
00079                 if (abs(measured_offset) > off):
00080                     st.level = DiagnosticStatus.WARN
00081                     st.message = "NTP Offset Too High"
00082                 if (abs(measured_offset) > self.error_offset):
00083                     st.level = DiagnosticStatus.ERROR
00084                     st.message = "NTP Offset Too High"
00085 
00086         except Exception, e:
00087             stat.level = DiagnosticStatus.ERROR
00088             stat.message = 'ntpdate Exception'
00089             stat.values = [ KeyValue(key = 'Exception', value = str(e)) ]
00090 
00091         self.msg = DiagnosticArray()
00092         self.msg.header.stamp = rospy.get_rostime()
00093         self.msg.status = [stat]
00094 
00095     def publish_diagnostics(self, event):
00096         self.diag_pub.publish(self.msg)
00097 
00098     def parse_args(self, argv=sys.argv):
00099         import optparse
00100         parser = optparse.OptionParser(usage="usage: ntp_monitor ntp-hostname []")
00101         parser.add_option("--offset", dest="offset",
00102                           action="store", default=500,
00103                           help="Offset from NTP host", metavar="OFFSET")
00104         parser.add_option("--error-offset", dest="error_offset",
00105                           action="store", default=5000000,
00106                           help="Offset from NTP host. Above this is error", metavar="OFFSET")
00107         parser.add_option("--diag-hostname", dest="diag_hostname",
00108                           help="Computer name in diagnostics output (ex: 'c1')",
00109                           metavar="DIAG_HOSTNAME",
00110                           action="store", default=None)
00111         options, args = parser.parse_args(rospy.myargv())
00112 
00113         if (len(args) != 2):
00114             parser.error("Invalid arguments. Must have HOSTNAME [args]. %s" % args)
00115             print('Invalid arguments.', file=sys.stderr)
00116             sys.exit(0)
00117 
00118         try:
00119             offset = int(options.offset)
00120             error_offset = int(options.error_offset)
00121         except:
00122             parser.error("Offsets must be numbers")
00123             print('Offsets must be numbers', file=sys.stderr)
00124             sys.exit(0)
00125 
00126         self.ntp_server = args[1]
00127         self.diag_hostname = options.diag_hostname
00128         hostname = socket.gethostname()
00129         if self.diag_hostname is None:
00130             self.diag_hostname = hostname
00131 
00132         self.offset = rospy.get_param('~offset', offset)
00133         self.error_offset = rospy.get_param('~error_offset', error_offset)
00134 
00135 
00136 if __name__ == "__main__":
00137     ntp = NtpMonitor(argv=sys.argv)
00138     rospy.spin()


cob_monitoring
Author(s): Florian Weisshardt , Felix Messmer
autogenerated on Sun Jun 9 2019 20:20:19