ntp_monitor.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
4 #
5 # Licensed under the Apache License, Version 2.0 (the "License");
6 # you may not use this file except in compliance with the License.
7 # You may obtain a copy of the License at
8 #
9 # http://www.apache.org/licenses/LICENSE-2.0
10 #
11 # Unless required by applicable law or agreed to in writing, software
12 # distributed under the License is distributed on an "AS IS" BASIS,
13 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 # See the License for the specific language governing permissions and
15 # limitations under the License.
16 
17 
18 
19 import sys
20 import traceback
21 import socket
22 from subprocess import Popen, PIPE
23 import time
24 import re
25 
26 import rospy
27 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
28 
29 class NtpMonitor():
30  def __init__(self, argv=sys.argv):
31  rospy.init_node("ntp_monitor")
32  self.parse_args(argv)
33 
34  stat = DiagnosticStatus()
35  stat.level = DiagnosticStatus.WARN
36  stat.name = '%s NTP Offset' % self.diag_hostname
37  stat.message = 'No Data'
38  stat.hardware_id = self.diag_hostname
39  stat.values = []
40  self.msg = DiagnosticArray()
41  self.msg.header.stamp = rospy.get_rostime()
42  self.msg.status = [stat]
43 
44  self.update_diagnostics()
45 
46  self.diag_pub = rospy.Publisher("/diagnostics", DiagnosticArray, queue_size=1)
47  self.diag_timer = rospy.Timer(rospy.Duration(1.0), self.publish_diagnostics)
48  self.monitor_timer = rospy.Timer(rospy.Duration(60.0), self.update_diagnostics)
49 
50  def update_diagnostics(self, event=None):
51  stat = DiagnosticStatus()
52  stat.level = DiagnosticStatus.WARN
53  stat.name = '%s NTP Offset' % self.diag_hostname
54  stat.message = 'No Data'
55  stat.hardware_id = self.diag_hostname
56  stat.values = []
57 
58  try:
59  for st,host,off in [(stat, self.ntp_server, self.offset)]:
60  p = Popen(["ntpdate", "-q", host], stdout=PIPE, stdin=PIPE, stderr=PIPE)
61  retcode = p.wait()
62  stdout, stderr = p.communicate()
63  try:
64  stdout = stdout.decode() #python3
65  stderr = stderr.decode() #python3
66  except (UnicodeDecodeError, AttributeError):
67  pass
68 
69  if retcode != 0:
70  st.level = DiagnosticStatus.ERROR
71  st.message = 'ntpdate Error'
72  st.values = [ KeyValue(key = 'ntpdate Error', value = stderr),
73  KeyValue(key = 'Output', value = stdout) ]
74  continue
75 
76  measured_offset = float(re.search("offset (.*),", stdout).group(1))*1000000
77 
78  st.level = DiagnosticStatus.OK
79  st.message = "OK"
80  st.values = [ KeyValue("NTP Server" , self.ntp_server),
81  KeyValue("Offset (us)", str(measured_offset)),
82  KeyValue("Offset tolerance (us)", str(off)),
83  KeyValue("Offset tolerance (us) for Error", str(self.error_offset)) ]
84 
85  if (abs(measured_offset) > off):
86  st.level = DiagnosticStatus.WARN
87  st.message = "NTP Offset Too High"
88  if (abs(measured_offset) > self.error_offset):
89  st.level = DiagnosticStatus.ERROR
90  st.message = "NTP Offset Too High"
91 
92  except Exception as e:
93  stat.level = DiagnosticStatus.ERROR
94  stat.message = 'ntpdate Exception'
95  stat.values = [ KeyValue(key = 'Exception', value = str(e)), KeyValue(key = 'Traceback', value = str(traceback.format_exc())) ]
96 
97  self.msg = DiagnosticArray()
98  self.msg.header.stamp = rospy.get_rostime()
99  self.msg.status = [stat]
100 
101  def publish_diagnostics(self, event):
102  self.diag_pub.publish(self.msg)
103 
104  def parse_args(self, argv=sys.argv):
105  import optparse
106  parser = optparse.OptionParser(usage="usage: ntp_monitor ntp-hostname []")
107  parser.add_option("--offset", dest="offset",
108  action="store", default=500,
109  help="Offset from NTP host", metavar="OFFSET")
110  parser.add_option("--error-offset", dest="error_offset",
111  action="store", default=5000000,
112  help="Offset from NTP host. Above this is error", metavar="OFFSET")
113  parser.add_option("--diag-hostname", dest="diag_hostname",
114  help="Computer name in diagnostics output (ex: 'c1')",
115  metavar="DIAG_HOSTNAME",
116  action="store", default=None)
117  options, args = parser.parse_args(rospy.myargv())
118 
119  if (len(args) != 2):
120  parser.error("Invalid arguments. Must have HOSTNAME [args]. %s" % args)
121  print('Invalid arguments.')
122  sys.exit(0)
123 
124  try:
125  offset = int(options.offset)
126  error_offset = int(options.error_offset)
127  except:
128  parser.error("Offsets must be numbers")
129  print('Offsets must be numbers')
130  sys.exit(0)
131 
132  self.ntp_server = args[1]
133  self.diag_hostname = options.diag_hostname
134  hostname = socket.gethostname()
135  if self.diag_hostname is None:
136  self.diag_hostname = hostname
137 
138  self.offset = rospy.get_param('~offset', offset)
139  self.error_offset = rospy.get_param('~error_offset', error_offset)
140 
141 
142 if __name__ == "__main__":
143  ntp = NtpMonitor(argv=sys.argv)
144  rospy.spin()
ntp_monitor.NtpMonitor.error_offset
error_offset
Definition: ntp_monitor.py:139
ntp_monitor.NtpMonitor.offset
offset
Definition: ntp_monitor.py:138
ntp_monitor.NtpMonitor.monitor_timer
monitor_timer
Definition: ntp_monitor.py:48
ntp_monitor.NtpMonitor.ntp_server
ntp_server
Definition: ntp_monitor.py:132
ntp_monitor.NtpMonitor.update_diagnostics
def update_diagnostics(self, event=None)
Definition: ntp_monitor.py:50
ntp_monitor.NtpMonitor.diag_pub
diag_pub
Definition: ntp_monitor.py:46
ntp_monitor.NtpMonitor.diag_timer
diag_timer
Definition: ntp_monitor.py:47
ntp_monitor.NtpMonitor.diag_hostname
diag_hostname
Definition: ntp_monitor.py:133
ntp_monitor.NtpMonitor.publish_diagnostics
def publish_diagnostics(self, event)
Definition: ntp_monitor.py:101
ntp_monitor.NtpMonitor
Definition: ntp_monitor.py:29
ntp_monitor.NtpMonitor.msg
msg
Definition: ntp_monitor.py:40
ntp_monitor.NtpMonitor.__init__
def __init__(self, argv=sys.argv)
Definition: ntp_monitor.py:30
ntp_monitor.NtpMonitor.parse_args
def parse_args(self, argv=sys.argv)
Definition: ntp_monitor.py:104


cob_monitoring
Author(s): Florian Weisshardt , Felix Messmer
autogenerated on Fri Aug 2 2024 09:45:52