Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixing ntp launchtest (#330) #391

Merged
merged 1 commit into from
Jul 22, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -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."""
Expand All @@ -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
Expand All @@ -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 = []
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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',
Expand Down Expand Up @@ -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)

Expand Down
1 change: 1 addition & 0 deletions diagnostic_common_diagnostics/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
<test_depend>ament_cmake_lint_cmake</test_depend>

<test_depend>ament_cmake_pytest</test_depend>
<test_depend>launch_testing_ament_cmake</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
130 changes: 0 additions & 130 deletions diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor.py

This file was deleted.

Loading