diff --git a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py index 8f4fcd06..461d17bd 100755 --- a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py +++ b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py @@ -45,7 +45,7 @@ class NTPMonitor(Node): """A diagnostic task that monitors the NTP offset of the system clock.""" - def __init__(self, ntp_hostname, offset=500, self_offset=500, + def __init__(self, ntp_hostname, ntp_port, offset=500, self_offset=500, diag_hostname=None, error_offset=5000000, do_self_test=True): """Initialize the NTPMonitor.""" @@ -54,6 +54,7 @@ def __init__(self, ntp_hostname, offset=500, self_offset=500, frequency = self.get_parameter('frequency').get_parameter_value().double_value self.ntp_hostname = ntp_hostname + self.ntp_port = ntp_port self.offset = offset self.self_offset = self_offset self.diag_hostname = diag_hostname @@ -67,7 +68,8 @@ def __init__(self, ntp_hostname, offset=500, self_offset=500, self.stat = DIAG.DiagnosticStatus() self.stat.level = DIAG.DiagnosticStatus.OK self.stat.name = 'NTP offset from ' + \ - self.diag_hostname + ' to ' + self.ntp_hostname + self.diag_hostname + ' to ' + self.ntp_hostname + \ + ':' + str(self.ntp_port) self.stat.message = 'OK' self.stat.hardware_id = self.hostname self.stat.values = [] @@ -128,7 +130,10 @@ def add_kv(stat_values, key, value): ntp_client = ntplib.NTPClient() response = None try: - response = ntp_client.request(self.ntp_hostname, version=3) + response = ntp_client.request( + self.ntp_hostname, + port=self.ntp_port, + version=3) except ntplib.NTPException as e: self.get_logger().error(f'NTP Error: {e}') st.level = DIAG.DiagnosticStatus.ERROR @@ -164,6 +169,9 @@ def ntp_monitor_main(argv=sys.argv[1:]): parser.add_argument('--ntp_hostname', action='store', default='0.pool.ntp.org', type=str) + parser.add_argument('--ntp_port', + action='store', default=123, + type=int) parser.add_argument('--offset-tolerance', dest='offset_tol', action='store', default=500, help='Offset from NTP host [us]', metavar='OFFSET-TOL', @@ -192,7 +200,8 @@ def ntp_monitor_main(argv=sys.argv[1:]): assert offset < error_offset, \ 'Offset tolerance must be less than error offset tolerance' - ntp_monitor = NTPMonitor(args.ntp_hostname, offset, self_offset, + ntp_monitor = NTPMonitor(args.ntp_hostname, args.ntp_port, + offset, self_offset, args.diag_hostname, error_offset, args.do_self_test) diff --git a/diagnostic_common_diagnostics/package.xml b/diagnostic_common_diagnostics/package.xml index 062bfdcd..3b008b6a 100644 --- a/diagnostic_common_diagnostics/package.xml +++ b/diagnostic_common_diagnostics/package.xml @@ -34,6 +34,7 @@ ament_cmake_lint_cmake ament_cmake_pytest + launch_testing_ament_cmake ament_cmake diff --git a/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor.py b/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor.py deleted file mode 100644 index 767ed2ac..00000000 --- a/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor.py +++ /dev/null @@ -1,130 +0,0 @@ -#!/usr/bin/env python3 -# -*- coding: utf-8 -*- -# Software License Agreement (BSD License) -# -# Copyright (c) 2023, Robert Bosch GmbH -# All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions -# are met: -# -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# * Redistributions in binary form must reproduce the above -# copyright notice, this list of conditions and the following -# disclaimer in the documentation and/or other materials provided -# with the distribution. -# * Neither the name of the Willow Garage nor the names of its -# contributors may be used to endorse or promote products derived -# from this software without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. - -import os -import subprocess -import unittest - -import ament_index_python - -from diagnostic_msgs.msg import DiagnosticArray - -import rclpy - -TIMEOUT_MAX_S = 5. - - -class TestNTPMonitor(unittest.TestCase): - - def __init__(self, methodName: str = 'runTest') -> None: - super().__init__(methodName) - rclpy.init() - self.n_msgs_received = 0 - - def setUp(self): - self.n_msgs_received = 0 - n = self._count_msgs(1.) - self.assertEqual(n, 0) - self.subprocess = subprocess.Popen( - [ - os.path.join( - ament_index_python.get_package_prefix( - 'diagnostic_common_diagnostics' - ), - 'lib', - 'diagnostic_common_diagnostics', - 'ntp_monitor.py' - ) - ] - ) - - def tearDown(self): - self.subprocess.kill() - - def _diagnostics_callback(self, msg): - rclpy.logging.get_logger('test_ntp_monitor').info( - f'Received diagnostics message: {msg}' - ) - search_strings = [ - 'NTP offset from', - 'NTP self-offset for' - ] - for search_string in search_strings: - if search_string in ''.join([ - s.name for s in msg.status - ]): - self.n_msgs_received += 1 - - def _count_msgs(self, timeout_s): - self.n_msgs_received = 0 - node = rclpy.create_node('test_ntp_monitor') - rclpy.logging.get_logger('test_ntp_monitor').info( - '_count_msgs' - ) - node.create_subscription( - DiagnosticArray, - 'diagnostics', - self._diagnostics_callback, - 1 - ) - TIME_D_S = .05 - waited_s = 0. - start = node.get_clock().now() - while waited_s < timeout_s and self.n_msgs_received == 0: - rclpy.spin_once(node, timeout_sec=TIME_D_S) - waited_s = (node.get_clock().now() - start).nanoseconds / 1e9 - rclpy.logging.get_logger('test_ntp_monitor').info( - f'received {self.n_msgs_received} messages after {waited_s}s' - ) - node.destroy_node() - return self.n_msgs_received - - def test_publishing(self): - self.assertEqual( - self.subprocess.poll(), - None, - 'NTP monitor subprocess died' - ) - - n = self._count_msgs(TIMEOUT_MAX_S) - - self.assertGreater( - n, - 0, - f'No messages received within {TIMEOUT_MAX_S}s' - ) - - -if __name__ == '__main__': - unittest.main()