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 ##### monkey-patch to suppress threading error message in python 2.7.3
49 ##### See http://stackoverflow.com/questions/13193278/understand-python-threading-bug
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  except OSError as e:
92  (errno, msg) = e.args
93  if errno == 4:
94  break #ctrl-c interrupt
95  else:
96  raise
97  if (res == 0):
98  measured_offset = float(re.search("offset (.*),", o).group(1))*1000000
99 
100  st.level = DiagnosticStatus.OK
101  st.message = "OK"
102  st.values = [ KeyValue("Offset (us)", str(measured_offset)),
103  KeyValue("Offset tolerance (us)", str(off)),
104  KeyValue("Offset tolerance (us) for Error", str(error_offset)) ]
105 
106  if (abs(measured_offset) > off):
107  st.level = DiagnosticStatus.WARN
108  st.message = "NTP Offset Too High"
109  if (abs(measured_offset) > error_offset):
110  st.level = DiagnosticStatus.ERROR
111  st.message = "NTP Offset Too High"
112 
113  else:
114  st.level = DiagnosticStatus.ERROR
115  st.message = "Error Running ntpdate. Returned %d" % res
116  st.values = [ KeyValue("Offset (us)", "N/A"),
117  KeyValue("Offset tolerance (us)", str(off)),
118  KeyValue("Offset tolerance (us) for Error", str(error_offset)),
119  KeyValue("Output", o),
120  KeyValue("Errors", e) ]
121  msg.status.append(st)
122 
123  msg.header.stamp = rospy.get_rostime()
124  pub.publish(msg)
125  time.sleep(1)
126 
127 def ntp_monitor_main(argv=sys.argv):
128  import optparse
129  parser = optparse.OptionParser(usage="usage: ntp_monitor ntp-hostname []")
130  parser.add_option("--offset-tolerance", dest="offset_tol",
131  action="store", default=500,
132  help="Offset from NTP host", metavar="OFFSET-TOL")
133  parser.add_option("--error-offset-tolerance", dest="error_offset_tol",
134  action="store", default=5000000,
135  help="Offset from NTP host. Above this is error", metavar="OFFSET-TOL")
136  parser.add_option("--self_offset-tolerance", dest="self_offset_tol",
137  action="store", default=500,
138  help="Offset from self", metavar="SELF_OFFSET-TOL")
139  parser.add_option("--diag-hostname", dest="diag_hostname",
140  help="Computer name in diagnostics output (ex: 'c1')",
141  metavar="DIAG_HOSTNAME",
142  action="store", default=None)
143  parser.add_option("--ignore-self", dest="ignore_self",
144  help="Ignore self NTP test", action="store_true")
145  options, args = parser.parse_args(rospy.myargv())
146 
147  if (len(args) != 2):
148  parser.error("Invalid arguments. Must have HOSTNAME [args]. %s" % args)
149 
150 
151  try:
152  offset = int(options.offset_tol)
153  self_offset = int(options.self_offset_tol)
154  error_offset = int(options.error_offset_tol)
155  ignore_self = options.ignore_self
156  except:
157  parser.error("Offsets must be numbers")
158 
159  ntp_monitor(args[1], offset, self_offset, options.diag_hostname,
160  error_offset, ignore_self)
161 
162 
163 if __name__ == "__main__":
164  try:
165  ntp_monitor_main(rospy.myargv())
166  except KeyboardInterrupt: pass
167  except SystemExit: pass
168  except:
169  import traceback
170  traceback.print_exc()
def ntp_monitor(ntp_hostname, offset=500, self_offset=500, diag_hostname=None, error_offset=5000000, ignore_self=False)
Definition: ntp_monitor.py:58
def ntp_monitor_main(argv=sys.argv)
Definition: ntp_monitor.py:127


pr2_computer_monitor
Author(s): Kevin Watts (watts@willowgarage.com)
autogenerated on Tue Jun 1 2021 02:50:51