ntp_monitor.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Software License Agreement (BSD License)
3 #
4 # Copyright (c) 2008, Willow Garage, Inc.
5 # All rights reserved.
6 #
7 # Redistribution and use in source and binary forms, with or without
8 # modification, are permitted provided that the following conditions
9 # are met:
10 #
11 # * Redistributions of source code must retain the above copyright
12 # notice, this list of conditions and the following disclaimer.
13 # * Redistributions in binary form must reproduce the above
14 # copyright notice, this list of conditions and the following
15 # disclaimer in the documentation and/or other materials provided
16 # with the distribution.
17 # * Neither the name of the Willow Garage nor the names of its
18 # contributors may be used to endorse or promote products derived
19 # from this software without specific prior written permission.
20 #
21 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 # POSSIBILITY OF SUCH DAMAGE.
33 
34 import roslib
35 roslib.load_manifest('pr2_computer_monitor')
36 
37 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
38 
39 import sys
40 import rospy
41 import socket
42 from subprocess import Popen, PIPE
43 
44 import time
45 
46 import re
47 
48 
50 if sys.version_info[:3] == (2, 7, 3):
51  import threading
52  threading._DummyThread._Thread__stop = lambda x: 42
53 
54 
55 NAME = 'ntp_monitor'
56 
57 def ntp_monitor(ntp_hostname, offset=500, self_offset=500, diag_hostname=None,
58  error_offset=5000000, ignore_self=False):
59  pub = rospy.Publisher("/diagnostics", DiagnosticArray, queue_size=10)
60  rospy.init_node(NAME, anonymous=True)
61 
62  hostname = socket.gethostname()
63  if diag_hostname is None:
64  diag_hostname = hostname
65 
66  ntp_checks = []
67  stat = DiagnosticStatus()
68  stat.level = 0
69  stat.name = "NTP offset from "+ diag_hostname + " to " + ntp_hostname
70  stat.message = "OK"
71  stat.hardware_id = hostname
72  stat.values = []
73  ntp_checks.append((stat, ntp_hostname, offset))
74 
75  if not ignore_self:
76  self_stat = DiagnosticStatus()
77  self_stat.level = DiagnosticStatus.OK
78  self_stat.name = "NTP self-offset for "+ diag_hostname
79  self_stat.message = "OK"
80  self_stat.hardware_id = hostname
81  self_stat.values = []
82  ntp_checks.append((self_stat, hostname, self_offset))
83 
84  while not rospy.is_shutdown():
85  msg = DiagnosticArray()
86  for st, host, off in ntp_checks:
87  try:
88  p = Popen(["ntpdate", "-q", host], stdout=PIPE, stdin=PIPE, stderr=PIPE)
89  res = p.wait()
90  (o,e) = p.communicate()
91  o = o.decode()
92  e = e.decode()
93  except OSError as e:
94  (errno, msg) = e.args
95  if errno == 4:
96  break #ctrl-c interrupt
97  else:
98  raise
99  if (res == 0):
100  measured_offset = float(re.search("offset (.*),", o).group(1))*1000000
101 
102  st.level = DiagnosticStatus.OK
103  st.message = "OK"
104  st.values = [ KeyValue("Offset (us)", str(measured_offset)),
105  KeyValue("Offset tolerance (us)", str(off)),
106  KeyValue("Offset tolerance (us) for Error", str(error_offset)) ]
107 
108  if (abs(measured_offset) > off):
109  st.level = DiagnosticStatus.WARN
110  st.message = "NTP Offset Too High"
111  if (abs(measured_offset) > error_offset):
112  st.level = DiagnosticStatus.ERROR
113  st.message = "NTP Offset Too High"
114  else:
115  st.level = DiagnosticStatus.WARN
116  st.message = "Error Running ntpdate. Returned %d" % res
117  st.values = [ KeyValue("Offset (us)", "N/A"),
118  KeyValue("Offset tolerance (us)", str(off)),
119  KeyValue("Offset tolerance (us) for Error", str(error_offset)),
120  KeyValue("Output", o),
121  KeyValue("Errors", e) ]
122  msg.status.append(st)
123 
124  msg.header.stamp = rospy.get_rostime()
125  pub.publish(msg)
126  time.sleep(1)
127 
128 def ntp_monitor_main(argv=sys.argv):
129  import optparse
130  parser = optparse.OptionParser(usage="usage: ntp_monitor ntp-hostname []")
131  parser.add_option("--offset-tolerance", dest="offset_tol",
132  action="store", default=500,
133  help="Offset from NTP host", metavar="OFFSET-TOL")
134  parser.add_option("--error-offset-tolerance", dest="error_offset_tol",
135  action="store", default=5000000,
136  help="Offset from NTP host. Above this is error", metavar="OFFSET-TOL")
137  parser.add_option("--self_offset-tolerance", dest="self_offset_tol",
138  action="store", default=500,
139  help="Offset from self", metavar="SELF_OFFSET-TOL")
140  parser.add_option("--diag-hostname", dest="diag_hostname",
141  help="Computer name in diagnostics output (ex: 'c1')",
142  metavar="DIAG_HOSTNAME",
143  action="store", default=None)
144  parser.add_option("--ignore-self", dest="ignore_self",
145  help="Ignore self NTP test", action="store_true")
146  options, args = parser.parse_args(rospy.myargv())
147 
148  if (len(args) != 2):
149  parser.error("Invalid arguments. Must have HOSTNAME [args]. %s" % args)
150 
151 
152  try:
153  offset = int(options.offset_tol)
154  self_offset = int(options.self_offset_tol)
155  error_offset = int(options.error_offset_tol)
156  ignore_self = options.ignore_self
157  except:
158  parser.error("Offsets must be numbers")
159 
160  ntp_monitor(args[1], offset, self_offset, options.diag_hostname,
161  error_offset, ignore_self)
162 
163 
164 if __name__ == "__main__":
165  try:
166  ntp_monitor_main(rospy.myargv())
167  except KeyboardInterrupt: pass
168  except SystemExit: pass
169  except:
170  import traceback
171  traceback.print_exc()
ntp_monitor.ntp_monitor
def ntp_monitor(ntp_hostname, offset=500, self_offset=500, diag_hostname=None, error_offset=5000000, ignore_self=False)
Definition: ntp_monitor.py:57
ntp_monitor.ntp_monitor_main
def ntp_monitor_main(argv=sys.argv)
Definition: ntp_monitor.py:128
ntp_monitor
Definition: ntp_monitor.py:1


pr2_computer_monitor
Author(s): Kevin Watts (watts@willowgarage.com)
autogenerated on Thu Sep 26 2024 02:53:24