From 9d88220da454fb0e3b6f1f7fcf3f4c74e903bba3 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Thu, 8 Feb 2024 12:48:34 +0100 Subject: [PATCH 01/27] new approach Signed-off-by: Christian Henkel --- .../ntp_monitor.py | 4 + .../systemtest/test_ntp_monitor_launchtest.py | 95 +++++++++++-------- 2 files changed, 62 insertions(+), 37 deletions(-) diff --git a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py index 4d52e9e84..117d7225a 100755 --- a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py +++ b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py @@ -155,6 +155,10 @@ def add_kv(stat_values, key, value): def ntp_monitor_main(argv=sys.argv[1:]): + # filter out ROS args + argv = [a for a in argv if not a.startswith('__') and not a == '--ros-args' and not a == '-r'] + + import argparse parser = argparse.ArgumentParser() parser.add_argument('--ntp_hostname', diff --git a/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py b/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py index d70470ed2..d0466d682 100644 --- a/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py +++ b/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py @@ -38,54 +38,75 @@ import launch +import launch_ros + import launch_pytest from launch_pytest.tools import process as process_tools +from launch_testing_ros import WaitForTopics + import launch_testing import pytest +import unittest + +import rclpy + +from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus + -@pytest.fixture -def ntp_monitor_proc(): +@pytest.mark.launch_test +def generate_test_description(): # Launch a process to test - return launch.actions.ExecuteProcess( - cmd=[ - os.path.join( - ament_index_python.get_package_prefix( - 'diagnostic_common_diagnostics'), - 'lib', - 'diagnostic_common_diagnostics', - 'ntp_monitor.py' - ), - ], - ), - - -@launch_pytest.fixture -def launch_description(ntp_monitor_proc): return launch.LaunchDescription([ - ntp_monitor_proc, + launch_ros.actions.Node( + package='diagnostic_common_diagnostics', + executable='ntp_monitor.py', + name='ntp_monitor', + output='screen', + arguments=['--offset-tolerance', '10000', '--error-offset-tolerance', '20000'] + # 10s, 20s, we are not testing if your clock is correct + ), launch_testing.actions.ReadyToTest() ]) -@pytest.mark.skip(reason='This test is not working yet') -@pytest.mark.launch(fixture=launch_description) -def test_read_stdout(ntp_monitor_proc, launch_context): - """Check if 'ntp_monitor' was found in the stdout.""" - def validate_output(output): - # this function can use assertions to validate the output or return a boolean. - # pytest generates easier to understand failures when assertions are used. - assert output.splitlines() == [ - 'ntp_monitor'], 'process never printed ntp_monitor' - process_tools.assert_output_sync( - launch_context, ntp_monitor_proc, validate_output, timeout=5) - - def validate_output(output): - return output == 'this will never happen' - assert not process_tools.wait_for_output_sync( - launch_context, ntp_monitor_proc, validate_output, timeout=0.1) - yield - # this is executed after launch service shutdown - assert ntp_monitor_proc.return_code == 0 +class TestGoodProcess(unittest.TestCase): + def __init__(self, methodName: str = "runTest") -> None: + super().__init__(methodName) + self.received_messages = [] + + def _received_message(self, msg): + self.received_messages.append(msg) + + def test_topic_published(self): + with WaitForTopics( + [('/diagnostics', DiagnosticArray)], + timeout=5 + ): + print('Topic found') + + rclpy.init() + test_node = rclpy.create_node('test_node') + test_node.create_subscription( + DiagnosticArray, + '/diagnostics', + self._received_message, + 1 + ) + + while len(self.received_messages) < 10: + rclpy.spin_once(test_node, timeout_sec=1) + + test_node.destroy_node() + + min_level = 10 + for msg in self.received_messages: + for status in msg.status: + level = int.from_bytes(status.level, byteorder='little') + print('Level: ', level) + if level < min_level: + min_level = level + + self.assertEqual(min_level, 0) \ No newline at end of file From 0fce9adbe1ddf12f523eb66ad27b3dfaf8097f74 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Thu, 21 Mar 2024 23:35:01 +0100 Subject: [PATCH 02/27] runs on container Signed-off-by: Christian Henkel --- .github/workflows/test.yaml | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index 2fe97d371..2c2d45fb4 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -24,12 +24,13 @@ jobs: distro: [humble, iron, rolling] include: - distro: humble - os: ubuntu-22.04 + os: 22.04 - distro: iron - os: ubuntu-22.04 + os: 22.04 - distro: rolling - os: ubuntu-22.04 - runs-on: ${{ matrix.os }} + os: 24.04 + runs-on: ubuntu-${{ matrix.os }} + container: ubuntu:${{ matrix.os }} steps: - uses: ros-tooling/setup-ros@master - run: | From e8fbbae27e4d6f4e5fbc4fcdf12d3c34c36c95d3 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Thu, 21 Mar 2024 23:39:31 +0100 Subject: [PATCH 03/27] all on ubuntu latest Signed-off-by: Christian Henkel --- .github/workflows/lint.yaml | 2 +- .github/workflows/test.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/lint.yaml b/.github/workflows/lint.yaml index 010a90157..3488e94ea 100644 --- a/.github/workflows/lint.yaml +++ b/.github/workflows/lint.yaml @@ -22,7 +22,7 @@ jobs: uncrustify, xmllint, ] - runs-on: ubuntu-22.04 + runs-on: ubuntu-latest env: AMENT_CPPCHECK_ALLOW_SLOW_VERSIONS: 1 steps: diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index 2c2d45fb4..aac96ba31 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -29,7 +29,7 @@ jobs: os: 22.04 - distro: rolling os: 24.04 - runs-on: ubuntu-${{ matrix.os }} + runs-on: ubuntu-latest container: ubuntu:${{ matrix.os }} steps: - uses: ros-tooling/setup-ros@master From 3c0cd2f464eae260414437fc666bc0562fc26a27 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Fri, 22 Mar 2024 16:40:45 +0100 Subject: [PATCH 04/27] trying fix Signed-off-by: Christian Henkel --- .github/workflows/test.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index aac96ba31..e98391a0b 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -32,7 +32,7 @@ jobs: runs-on: ubuntu-latest container: ubuntu:${{ matrix.os }} steps: - - uses: ros-tooling/setup-ros@master + - uses: ct2034/setup-ros@patch-1 - run: | sudo pip install pydocstyle==6.1.1 # downgrade to fix https://github.com/ament/ament_lint/pull/428 sudo pip install pip --upgrade From 01bf2f15d5cd98ae02b90b8a78134d8b3e55eda4 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Tue, 26 Mar 2024 16:41:11 +0100 Subject: [PATCH 05/27] flake8 Signed-off-by: Christian Henkel --- .../ntp_monitor.py | 1 - .../systemtest/test_ntp_monitor_launchtest.py | 24 +++++++------------ 2 files changed, 9 insertions(+), 16 deletions(-) diff --git a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py index 117d7225a..cae035877 100755 --- a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py +++ b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py @@ -158,7 +158,6 @@ def ntp_monitor_main(argv=sys.argv[1:]): # filter out ROS args argv = [a for a in argv if not a.startswith('__') and not a == '--ros-args' and not a == '-r'] - import argparse parser = argparse.ArgumentParser() parser.add_argument('--ntp_hostname', diff --git a/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py b/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py index d0466d682..bc2929153 100644 --- a/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py +++ b/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py @@ -32,29 +32,22 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -import os +import unittest -import ament_index_python +from diagnostic_msgs.msg import DiagnosticArray import launch import launch_ros -import launch_pytest -from launch_pytest.tools import process as process_tools +import launch_testing from launch_testing_ros import WaitForTopics -import launch_testing - import pytest -import unittest - import rclpy -from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus - @pytest.mark.launch_test def generate_test_description(): @@ -65,7 +58,8 @@ def generate_test_description(): executable='ntp_monitor.py', name='ntp_monitor', output='screen', - arguments=['--offset-tolerance', '10000', '--error-offset-tolerance', '20000'] + arguments=['--offset-tolerance', '10000', + '--error-offset-tolerance', '20000'] # 10s, 20s, we are not testing if your clock is correct ), launch_testing.actions.ReadyToTest() @@ -73,7 +67,7 @@ def generate_test_description(): class TestGoodProcess(unittest.TestCase): - def __init__(self, methodName: str = "runTest") -> None: + def __init__(self, methodName: str = 'runTest') -> None: super().__init__(methodName) self.received_messages = [] @@ -86,7 +80,7 @@ def test_topic_published(self): timeout=5 ): print('Topic found') - + rclpy.init() test_node = rclpy.create_node('test_node') test_node.create_subscription( @@ -108,5 +102,5 @@ def test_topic_published(self): print('Level: ', level) if level < min_level: min_level = level - - self.assertEqual(min_level, 0) \ No newline at end of file + + self.assertEqual(min_level, 0) From e5473f24b68ded480b616fe8bafa23d12c0aa4f0 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Tue, 26 Mar 2024 16:53:51 +0100 Subject: [PATCH 06/27] Better way to find min over received data Signed-off-by: Christian Henkel --- .../systemtest/test_ntp_monitor_launchtest.py | 24 ++++++++++++------- 1 file changed, 15 insertions(+), 9 deletions(-) diff --git a/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py b/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py index bc2929153..e79ee1f10 100644 --- a/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py +++ b/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py @@ -66,7 +66,7 @@ def generate_test_description(): ]) -class TestGoodProcess(unittest.TestCase): +class TestNtpMonitor(unittest.TestCase): def __init__(self, methodName: str = 'runTest') -> None: super().__init__(methodName) self.received_messages = [] @@ -74,6 +74,15 @@ def __init__(self, methodName: str = 'runTest') -> None: def _received_message(self, msg): self.received_messages.append(msg) + def _get_min_level(self): + levels = [ + int.from_bytes(status.level, 'little') + for diag in self.received_messages + for status in diag.status] + if len(levels) == 0: + return -1 + return min(levels) + def test_topic_published(self): with WaitForTopics( [('/diagnostics', DiagnosticArray)], @@ -92,15 +101,12 @@ def test_topic_published(self): while len(self.received_messages) < 10: rclpy.spin_once(test_node, timeout_sec=1) + if (min_level := self._get_min_level()) == 0: + break test_node.destroy_node() - - min_level = 10 + rclpy.shutdown() + print(f'Got {len(self.received_messages)} messages:') for msg in self.received_messages: - for status in msg.status: - level = int.from_bytes(status.level, byteorder='little') - print('Level: ', level) - if level < min_level: - min_level = level - + print(msg) self.assertEqual(min_level, 0) From 6ff5bd93a2fd58654e586cdb9a4d9b2ea880a988 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Tue, 26 Mar 2024 16:59:10 +0100 Subject: [PATCH 07/27] using https://github.com/ros-tooling/setup-ros/pull/658 Signed-off-by: Christian Henkel --- .github/workflows/test.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index e98391a0b..2fd068980 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -32,7 +32,7 @@ jobs: runs-on: ubuntu-latest container: ubuntu:${{ matrix.os }} steps: - - uses: ct2034/setup-ros@patch-1 + - uses: christophebedard/setup-ros@ubuntu-noble-rolling - run: | sudo pip install pydocstyle==6.1.1 # downgrade to fix https://github.com/ament/ament_lint/pull/428 sudo pip install pip --upgrade From 31d094c2dcd68f79b2cddd0801942a57f23308e9 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Tue, 26 Mar 2024 17:01:07 +0100 Subject: [PATCH 08/27] naming Signed-off-by: Christian Henkel --- .github/workflows/test.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index 2fd068980..440205865 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -32,7 +32,7 @@ jobs: runs-on: ubuntu-latest container: ubuntu:${{ matrix.os }} steps: - - uses: christophebedard/setup-ros@ubuntu-noble-rolling + - uses: ros-tooling/setup-ros@christophebedard/ubuntu-noble-rolling - run: | sudo pip install pydocstyle==6.1.1 # downgrade to fix https://github.com/ament/ament_lint/pull/428 sudo pip install pip --upgrade From 5a124e2df8d9982822b40e72b007bfe6527ff78f Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Tue, 26 Mar 2024 17:03:33 +0100 Subject: [PATCH 09/27] pydocstyle fix is obsolete Signed-off-by: Christian Henkel --- .github/workflows/test.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index 440205865..00915df5f 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -34,7 +34,6 @@ jobs: steps: - uses: ros-tooling/setup-ros@christophebedard/ubuntu-noble-rolling - run: | - sudo pip install pydocstyle==6.1.1 # downgrade to fix https://github.com/ament/ament_lint/pull/428 sudo pip install pip --upgrade sudo pip install pyopenssl --upgrade # fix for AttributeError: module 'lib' has no attribute 'X509_V_FLAG_CB_ISSUER_CHECK' - uses: ros-tooling/action-ros-ci@master From 49bb501044d33f6b26ca8494903581d9d99fdb79 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Tue, 26 Mar 2024 17:05:18 +0100 Subject: [PATCH 10/27] No pip fixes any more Signed-off-by: Christian Henkel --- .github/workflows/test.yaml | 3 --- 1 file changed, 3 deletions(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index 00915df5f..c0f01eb90 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -33,9 +33,6 @@ jobs: container: ubuntu:${{ matrix.os }} steps: - uses: ros-tooling/setup-ros@christophebedard/ubuntu-noble-rolling - - run: | - sudo pip install pip --upgrade - sudo pip install pyopenssl --upgrade # fix for AttributeError: module 'lib' has no attribute 'X509_V_FLAG_CB_ISSUER_CHECK' - uses: ros-tooling/action-ros-ci@master with: target-ros2-distro: ${{ matrix.distro }} From bb7458718f9ce5b746b62b5f24ab0fb86b23e219 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Tue, 26 Mar 2024 17:21:59 +0100 Subject: [PATCH 11/27] exchanging test to run in Cmakelists Signed-off-by: Christian Henkel --- diagnostic_common_diagnostics/CMakeLists.txt | 8 +- .../test/systemtest/test_ntp_monitor.py | 130 ------------------ 2 files changed, 4 insertions(+), 134 deletions(-) delete mode 100644 diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor.py diff --git a/diagnostic_common_diagnostics/CMakeLists.txt b/diagnostic_common_diagnostics/CMakeLists.txt index 5c0f11f6b..cf1b78027 100644 --- a/diagnostic_common_diagnostics/CMakeLists.txt +++ b/diagnostic_common_diagnostics/CMakeLists.txt @@ -22,10 +22,10 @@ if(BUILD_TESTING) test_cpu_monitor test/systemtest/test_cpu_monitor.py TIMEOUT 10) - ament_add_pytest_test( - test_ntp_monitor - test/systemtest/test_ntp_monitor.py - TIMEOUT 10) + add_launch_test( + test/systemtest/test_ntp_monitor_launchtest.py + TARGET ntp_monitor_launchtest + TIMEOUT 20) endif() ament_package() 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 767ed2ac6..000000000 --- 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() From 7592bfbf72ee5188f041731c8ae3d2cf4713eeb8 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Tue, 26 Mar 2024 17:27:22 +0100 Subject: [PATCH 12/27] cmake Signed-off-by: Christian Henkel --- diagnostic_common_diagnostics/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/diagnostic_common_diagnostics/CMakeLists.txt b/diagnostic_common_diagnostics/CMakeLists.txt index cf1b78027..e62c86ec0 100644 --- a/diagnostic_common_diagnostics/CMakeLists.txt +++ b/diagnostic_common_diagnostics/CMakeLists.txt @@ -15,6 +15,7 @@ install(PROGRAMS if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) + find_package(launch_testing_ament_cmake REQUIRED) ament_lint_auto_find_test_dependencies() find_package(ament_cmake_pytest REQUIRED) From e797c65d5043bb205bd2a60d09f090f258f4ff40 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Tue, 26 Mar 2024 17:31:20 +0100 Subject: [PATCH 13/27] flake8<5 on noble Signed-off-by: Christian Henkel --- .github/workflows/test.yaml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index c0f01eb90..02483864b 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -33,6 +33,10 @@ jobs: container: ubuntu:${{ matrix.os }} steps: - uses: ros-tooling/setup-ros@christophebedard/ubuntu-noble-rolling + - run: + sudo apt install -y python3-pip + pip3 install flake8<5 # fix flake8.exceptions.FailedToLoadPlugin: Flake8 failed to load plugin "pycodestyle" due to cannot import name 'missing_whitespace_around_operator' from 'pycodestyle' (/usr/lib/python3/dist-packages/pycodestyle.py). + if: ${{ matrix.os }} == '24.04' - uses: ros-tooling/action-ros-ci@master with: target-ros2-distro: ${{ matrix.distro }} From 2a5dc9784e824be1f4bb210c2c9f8f51d53f4499 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Tue, 26 Mar 2024 17:35:35 +0100 Subject: [PATCH 14/27] | Signed-off-by: Christian Henkel --- .github/workflows/test.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index 02483864b..a1fa873cb 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -33,7 +33,7 @@ jobs: container: ubuntu:${{ matrix.os }} steps: - uses: ros-tooling/setup-ros@christophebedard/ubuntu-noble-rolling - - run: + - run: | sudo apt install -y python3-pip pip3 install flake8<5 # fix flake8.exceptions.FailedToLoadPlugin: Flake8 failed to load plugin "pycodestyle" due to cannot import name 'missing_whitespace_around_operator' from 'pycodestyle' (/usr/lib/python3/dist-packages/pycodestyle.py). if: ${{ matrix.os }} == '24.04' From 4955f55363dc8b592defd855ec61b8f60f90de7a Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Tue, 26 Mar 2024 17:37:51 +0100 Subject: [PATCH 15/27] string Signed-off-by: Christian Henkel --- .github/workflows/test.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index a1fa873cb..b79a2b423 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -35,7 +35,7 @@ jobs: - uses: ros-tooling/setup-ros@christophebedard/ubuntu-noble-rolling - run: | sudo apt install -y python3-pip - pip3 install flake8<5 # fix flake8.exceptions.FailedToLoadPlugin: Flake8 failed to load plugin "pycodestyle" due to cannot import name 'missing_whitespace_around_operator' from 'pycodestyle' (/usr/lib/python3/dist-packages/pycodestyle.py). + pip3 install 'flake8<5' # fix flake8.exceptions.FailedToLoadPlugin: Flake8 failed to load plugin "pycodestyle" due to cannot import name 'missing_whitespace_around_operator' from 'pycodestyle' (/usr/lib/python3/dist-packages/pycodestyle.py). if: ${{ matrix.os }} == '24.04' - uses: ros-tooling/action-ros-ci@master with: From cc484f133fd497bf4f3a983bf0f378a8be1e343f Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Tue, 26 Mar 2024 17:40:15 +0100 Subject: [PATCH 16/27] --break-system-packages Signed-off-by: Christian Henkel --- .github/workflows/test.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index b79a2b423..5fd74c09a 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -35,7 +35,7 @@ jobs: - uses: ros-tooling/setup-ros@christophebedard/ubuntu-noble-rolling - run: | sudo apt install -y python3-pip - pip3 install 'flake8<5' # fix flake8.exceptions.FailedToLoadPlugin: Flake8 failed to load plugin "pycodestyle" due to cannot import name 'missing_whitespace_around_operator' from 'pycodestyle' (/usr/lib/python3/dist-packages/pycodestyle.py). + pip3 install 'flake8<5' --break-system-packages # fix flake8.exceptions.FailedToLoadPlugin: Flake8 failed to load plugin "pycodestyle" due to cannot import name 'missing_whitespace_around_operator' from 'pycodestyle' (/usr/lib/python3/dist-packages/pycodestyle.py). if: ${{ matrix.os }} == '24.04' - uses: ros-tooling/action-ros-ci@master with: From 2552d5a3a724bd833ba4201c79f007807f9aa7dc Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Tue, 26 Mar 2024 17:42:48 +0100 Subject: [PATCH 17/27] order of arguments Signed-off-by: Christian Henkel --- .github/workflows/test.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index 5fd74c09a..39e289541 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -35,7 +35,7 @@ jobs: - uses: ros-tooling/setup-ros@christophebedard/ubuntu-noble-rolling - run: | sudo apt install -y python3-pip - pip3 install 'flake8<5' --break-system-packages # fix flake8.exceptions.FailedToLoadPlugin: Flake8 failed to load plugin "pycodestyle" due to cannot import name 'missing_whitespace_around_operator' from 'pycodestyle' (/usr/lib/python3/dist-packages/pycodestyle.py). + pip3 install --break-system-packages 'flake8<5' # fix flake8.exceptions.FailedToLoadPlugin: Flake8 failed to load plugin "pycodestyle" due to cannot import name 'missing_whitespace_around_operator' from 'pycodestyle' (/usr/lib/python3/dist-packages/pycodestyle.py). if: ${{ matrix.os }} == '24.04' - uses: ros-tooling/action-ros-ci@master with: From c46be6b4240644f80f1af41e9bac6a2d59e3cec7 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Tue, 26 Mar 2024 17:52:54 +0100 Subject: [PATCH 18/27] ~ Signed-off-by: Christian Henkel --- .github/workflows/test.yaml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index 39e289541..ab472474a 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -35,8 +35,9 @@ jobs: - uses: ros-tooling/setup-ros@christophebedard/ubuntu-noble-rolling - run: | sudo apt install -y python3-pip + python3 -m pip install --upgrade pip pip3 install --break-system-packages 'flake8<5' # fix flake8.exceptions.FailedToLoadPlugin: Flake8 failed to load plugin "pycodestyle" due to cannot import name 'missing_whitespace_around_operator' from 'pycodestyle' (/usr/lib/python3/dist-packages/pycodestyle.py). - if: ${{ matrix.os }} == '24.04' + if: ${{ matrix.os == '24.04' }} - uses: ros-tooling/action-ros-ci@master with: target-ros2-distro: ${{ matrix.distro }} From 3eedcb714bcfb78d982f3931b4cbd16539c0e73d Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Tue, 26 Mar 2024 17:55:59 +0100 Subject: [PATCH 19/27] updating pip wont work Signed-off-by: Christian Henkel --- .github/workflows/test.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index ab472474a..4e5ddfc4b 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -35,7 +35,6 @@ jobs: - uses: ros-tooling/setup-ros@christophebedard/ubuntu-noble-rolling - run: | sudo apt install -y python3-pip - python3 -m pip install --upgrade pip pip3 install --break-system-packages 'flake8<5' # fix flake8.exceptions.FailedToLoadPlugin: Flake8 failed to load plugin "pycodestyle" due to cannot import name 'missing_whitespace_around_operator' from 'pycodestyle' (/usr/lib/python3/dist-packages/pycodestyle.py). if: ${{ matrix.os == '24.04' }} - uses: ros-tooling/action-ros-ci@master From 4869f248fc6d626c2676924bdd2be73edc3a834a Mon Sep 17 00:00:00 2001 From: Christian Henkel <6976069+ct2034@users.noreply.github.com> Date: Wed, 27 Mar 2024 18:14:31 +0100 Subject: [PATCH 20/27] Back to master --- .github/workflows/test.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index 4e5ddfc4b..750217c6a 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -32,7 +32,7 @@ jobs: runs-on: ubuntu-latest container: ubuntu:${{ matrix.os }} steps: - - uses: ros-tooling/setup-ros@christophebedard/ubuntu-noble-rolling + - uses: ros-tooling/setup-ros@master - run: | sudo apt install -y python3-pip pip3 install --break-system-packages 'flake8<5' # fix flake8.exceptions.FailedToLoadPlugin: Flake8 failed to load plugin "pycodestyle" due to cannot import name 'missing_whitespace_around_operator' from 'pycodestyle' (/usr/lib/python3/dist-packages/pycodestyle.py). From 6e8c40c2644fb6a72d23eefb555438d894e87e72 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Thu, 28 Mar 2024 09:12:00 +0100 Subject: [PATCH 21/27] no fixes Signed-off-by: Christian Henkel --- .github/workflows/test.yaml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index 750217c6a..4d1497641 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -33,10 +33,10 @@ jobs: container: ubuntu:${{ matrix.os }} steps: - uses: ros-tooling/setup-ros@master - - run: | - sudo apt install -y python3-pip - pip3 install --break-system-packages 'flake8<5' # fix flake8.exceptions.FailedToLoadPlugin: Flake8 failed to load plugin "pycodestyle" due to cannot import name 'missing_whitespace_around_operator' from 'pycodestyle' (/usr/lib/python3/dist-packages/pycodestyle.py). - if: ${{ matrix.os == '24.04' }} + # - run: | + # sudo apt install -y python3-pip + # pip3 install --break-system-packages 'flake8<5' # fix flake8.exceptions.FailedToLoadPlugin: Flake8 failed to load plugin "pycodestyle" due to cannot import name 'missing_whitespace_around_operator' from 'pycodestyle' (/usr/lib/python3/dist-packages/pycodestyle.py). + # if: ${{ matrix.os == '24.04' }} - uses: ros-tooling/action-ros-ci@master with: target-ros2-distro: ${{ matrix.distro }} From d2b92fd8349ce900efe282c29ee9de0e90850058 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Thu, 28 Mar 2024 09:25:37 +0100 Subject: [PATCH 22/27] no uncrustify Signed-off-by: Christian Henkel --- self_test/CMakeLists.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/self_test/CMakeLists.txt b/self_test/CMakeLists.txt index 0acbaa640..46401f9ed 100644 --- a/self_test/CMakeLists.txt +++ b/self_test/CMakeLists.txt @@ -67,6 +67,10 @@ if(BUILD_TESTING) set(ament_cmake_copyright_FOUND TRUE) ament_lint_auto_find_test_dependencies() + list(APPEND AMENT_LINT_AUTO_EXCLUDE + ament_cmake_uncrustify # Inconsistent between jammy and noble + ) + add_subdirectory(test) endif() From 1cd70065c6c7638b1ce16fe760ce8671a7e8536e Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Thu, 28 Mar 2024 09:34:52 +0100 Subject: [PATCH 23/27] flake8 Signed-off-by: Christian Henkel --- .../test/systemtest/test_ntp_monitor_launchtest.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py b/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py index e79ee1f10..f935d6ce3 100644 --- a/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py +++ b/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py @@ -51,7 +51,7 @@ @pytest.mark.launch_test def generate_test_description(): - # Launch a process to test + """Launch the ntp_monitor node and return a launch description.""" return launch.LaunchDescription([ launch_ros.actions.Node( package='diagnostic_common_diagnostics', @@ -67,6 +67,8 @@ def generate_test_description(): class TestNtpMonitor(unittest.TestCase): + """Test if the ntp_monitor node is publishing diagnostics.""" + def __init__(self, methodName: str = 'runTest') -> None: super().__init__(methodName) self.received_messages = [] @@ -84,6 +86,8 @@ def _get_min_level(self): return min(levels) def test_topic_published(self): + """Test if the ntp_monitor node is publishing diagnostics.""" + with WaitForTopics( [('/diagnostics', DiagnosticArray)], timeout=5 From 702c51764f8d3eb5e0bcb6e08dc6f3d1c59c101c Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Thu, 28 Mar 2024 09:41:56 +0100 Subject: [PATCH 24/27] deleting unused code Signed-off-by: Christian Henkel --- .github/workflows/test.yaml | 4 ---- 1 file changed, 4 deletions(-) diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml index 4d1497641..1e07c0adc 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -33,10 +33,6 @@ jobs: container: ubuntu:${{ matrix.os }} steps: - uses: ros-tooling/setup-ros@master - # - run: | - # sudo apt install -y python3-pip - # pip3 install --break-system-packages 'flake8<5' # fix flake8.exceptions.FailedToLoadPlugin: Flake8 failed to load plugin "pycodestyle" due to cannot import name 'missing_whitespace_around_operator' from 'pycodestyle' (/usr/lib/python3/dist-packages/pycodestyle.py). - # if: ${{ matrix.os == '24.04' }} - uses: ros-tooling/action-ros-ci@master with: target-ros2-distro: ${{ matrix.distro }} From 07582fc3e01401b59ae57dc44b684354341c9e40 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Thu, 28 Mar 2024 09:48:35 +0100 Subject: [PATCH 25/27] missing dependency Signed-off-by: Christian Henkel --- diagnostic_common_diagnostics/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/diagnostic_common_diagnostics/package.xml b/diagnostic_common_diagnostics/package.xml index de8808d70..8496593a0 100644 --- a/diagnostic_common_diagnostics/package.xml +++ b/diagnostic_common_diagnostics/package.xml @@ -33,6 +33,7 @@ ament_cmake_lint_cmake ament_cmake_pytest + launch_testing_ament_cmake ament_cmake From 8b6d701fbff6156cca3d1391a53a4a3fcb441e71 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Thu, 28 Mar 2024 10:01:42 +0100 Subject: [PATCH 26/27] fix as suggested in https://github.com/cf-natali/ntplib/issues/32 Signed-off-by: Christian Henkel --- .../ntp_monitor.py | 17 +++++++++++++---- 1 file changed, 13 insertions(+), 4 deletions(-) diff --git a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py index cae035877..aa1813c45 100755 --- a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py +++ b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py @@ -47,13 +47,14 @@ 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.""" super().__init__(__class__.__name__) 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 = [] @@ -127,7 +129,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 @@ -163,6 +168,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', @@ -191,7 +199,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) From dbd5b68ee1233db708a797d69267df863c906d13 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Thu, 28 Mar 2024 10:13:18 +0100 Subject: [PATCH 27/27] flake8 Signed-off-by: Christian Henkel --- .../diagnostic_common_diagnostics/ntp_monitor.py | 2 +- .../test/systemtest/test_ntp_monitor_launchtest.py | 1 - 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py index aa1813c45..9462cebb3 100755 --- a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py +++ b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py @@ -199,7 +199,7 @@ 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, args.ntp_port, + 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/test/systemtest/test_ntp_monitor_launchtest.py b/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py index f935d6ce3..495c9b684 100644 --- a/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py +++ b/diagnostic_common_diagnostics/test/systemtest/test_ntp_monitor_launchtest.py @@ -87,7 +87,6 @@ def _get_min_level(self): def test_topic_published(self): """Test if the ntp_monitor node is publishing diagnostics.""" - with WaitForTopics( [('/diagnostics', DiagnosticArray)], timeout=5