35 roslib.load_manifest(
'pr2_computer_monitor')
37 from diagnostic_msgs.msg
import DiagnosticArray, DiagnosticStatus, KeyValue
42 from subprocess
import Popen, PIPE
50 if sys.version_info[:3] == (2, 7, 3):
52 threading._DummyThread._Thread__stop =
lambda x: 42
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)
62 hostname = socket.gethostname()
63 if diag_hostname
is None:
64 diag_hostname = hostname
67 stat = DiagnosticStatus()
69 stat.name =
"NTP offset from "+ diag_hostname +
" to " + ntp_hostname
71 stat.hardware_id = hostname
73 ntp_checks.append((stat, ntp_hostname, offset))
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
82 ntp_checks.append((self_stat, hostname, self_offset))
84 while not rospy.is_shutdown():
85 msg = DiagnosticArray()
86 for st, host, off
in ntp_checks:
88 p = Popen([
"ntpdate",
"-q", host], stdout=PIPE, stdin=PIPE, stderr=PIPE)
90 (o,e) = p.communicate()
98 measured_offset = float(re.search(
"offset (.*),", o).group(1))*1000000
100 st.level = DiagnosticStatus.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)) ]
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" 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)
123 msg.header.stamp = rospy.get_rostime()
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())
148 parser.error(
"Invalid arguments. Must have HOSTNAME [args]. %s" % args)
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
157 parser.error(
"Offsets must be numbers")
159 ntp_monitor(args[1], offset, self_offset, options.diag_hostname,
160 error_offset, ignore_self)
163 if __name__ ==
"__main__":
166 except KeyboardInterrupt:
pass 167 except SystemExit:
pass 170 traceback.print_exc()
def ntp_monitor(ntp_hostname, offset=500, self_offset=500, diag_hostname=None, error_offset=5000000, ignore_self=False)
def ntp_monitor_main(argv=sys.argv)