36 roslib.load_manifest(
'diagnostic_common_diagnostics')
 
   38 import diagnostic_updater 
as DIAG
 
   43 from subprocess 
import Popen, PIPE
 
   50         p = Popen([
"ntpdate", 
"-q", host], stdout=PIPE, stdin=PIPE, stderr=PIPE)
 
   52         (o,e) = p.communicate()
 
   53     except OSError 
as errno:
 
   59         measured_offset = float(re.search(
"offset (.*),", o.decode()).group(1))*1000000
 
   61         st.level = DIAG.DiagnosticStatus.OK
 
   63         st.values = [ DIAG.KeyValue(
"Offset (us)", str(measured_offset)),
 
   64                         DIAG.KeyValue(
"Offset tolerance (us)", str(off)),
 
   65                         DIAG.KeyValue(
"Offset tolerance (us) for Error", str(error_offset)) ]
 
   67         if (abs(measured_offset) > off):
 
   68             st.level = DIAG.DiagnosticStatus.WARN
 
   69             st.message = 
"NTP Offset Too High" 
   70         if (abs(measured_offset) > error_offset):
 
   71             st.level = DIAG.DiagnosticStatus.ERROR
 
   72             st.message = 
"NTP Offset Too High" 
   75         st.level = DIAG.DiagnosticStatus.ERROR
 
   76         st.message = 
"Error Running ntpdate. Returned %d" % res
 
   77         st.values = [ DIAG.KeyValue(
"Offset (us)", 
"N/A"),
 
   78                         DIAG.KeyValue(
"Offset tolerance (us)", str(off)),
 
   79                         DIAG.KeyValue(
"Offset tolerance (us) for Error", str(error_offset)),
 
   80                         DIAG.KeyValue(
"Output", o.decode()),
 
   81                         DIAG.KeyValue(
"Errors", e.decode()) ]
 
   88     def __init__(self, ntp_hostname, offset=500, self_offset=500,
 
   89                  diag_hostname = None, error_offset = 5000000,
 
  103         self.
stat = DIAG.DiagnosticStatus()
 
  104         self.
stat.level = DIAG.DiagnosticStatus.OK
 
  106         self.
stat.message = 
"OK" 
  111         self.
self_stat.level = DIAG.DiagnosticStatus.OK
 
  117         self.
mutex = threading.Lock()
 
  118         self.
pub = rospy.Publisher(
"/diagnostics", DIAG.DiagnosticArray, queue_size=10)
 
  131         new_msg = DIAG.DiagnosticArray()
 
  132         new_msg.header.stamp = rospy.get_rostime()
 
  136             new_msg.status.append(st)
 
  141                 new_msg.status.append(st)
 
  151     parser = optparse.OptionParser(usage=
"usage: ntp_monitor ntp-hostname []")
 
  152     parser.add_option(
"--offset-tolerance", dest=
"offset_tol",
 
  153                       action=
"store", default=500,
 
  154                       help=
"Offset from NTP host", metavar=
"OFFSET-TOL")
 
  155     parser.add_option(
"--error-offset-tolerance", dest=
"error_offset_tol",
 
  156                       action=
"store", default=5000000,
 
  157                       help=
"Offset from NTP host. Above this is error", metavar=
"OFFSET-TOL")
 
  158     parser.add_option(
"--self_offset-tolerance", dest=
"self_offset_tol",
 
  159                       action=
"store", default=500,
 
  160                       help=
"Offset from self", metavar=
"SELF_OFFSET-TOL")
 
  161     parser.add_option(
"--diag-hostname", dest=
"diag_hostname",
 
  162                       help=
"Computer name in diagnostics output (ex: 'c1')",
 
  163                       metavar=
"DIAG_HOSTNAME",
 
  164                       action=
"store", default=
None)
 
  165     parser.add_option(
"--no-self-test", dest=
"do_self_test",
 
  166                       help=
"Disable self test",
 
  167                       action=
"store_false", default=
True)
 
  168     options, args = parser.parse_args(rospy.myargv())
 
  171         parser.error(
"Invalid arguments. Must have HOSTNAME [args]. %s" % args)
 
  175         offset = int(options.offset_tol)
 
  176         self_offset = int(options.self_offset_tol)
 
  177         error_offset = int(options.error_offset_tol)
 
  179         parser.error(
"Offsets must be numbers")
 
  181     ntp_monitor = 
NTPMonitor(args[1], offset, self_offset,
 
  182                              options.diag_hostname, error_offset,
 
  183                              options.do_self_test)
 
  187 if __name__ == 
"__main__":
 
  188     rospy.init_node(
"ntp_monitor", anonymous=
True)
 
  191     except KeyboardInterrupt: 
pass 
  192     except SystemExit: 
pass 
  195         traceback.print_exc()