From b1c8dd16694869b9bc8d778ef0386b9f5dba7437 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Thu, 21 Mar 2024 23:20:28 +0100 Subject: [PATCH 1/7] documentation on new branch Signed-off-by: Christian Henkel --- README.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/README.md b/README.md index 727ac3af..70032ebf 100644 --- a/README.md +++ b/README.md @@ -40,6 +40,10 @@ The [`ros2` branch](https://github.com/ros/diagnostics/tree/ros2) targets - *Iron Irwini* and - *Rolling Ridley* +The [`ros2-jazzy` branch](https://github.com/ros/diagnostics/tree/ros2-jazzy) targets + +- *Jazzy Jalisco* + # License The source code is released under a [BSD 3-Clause license](LICENSE). From f89beba1b2c8537399e0e38986d6f2356d5a1ebd Mon Sep 17 00:00:00 2001 From: Richard <47382675+RichardvdK@users.noreply.github.com> Date: Fri, 22 Mar 2024 11:37:13 +0100 Subject: [PATCH 2/7] Port cpu_monitor to ROS2 (#326) * add cpu monitor to the common diagnostics * add 3 unittests * add psutil to package xml * add debug print for cpu percentages and change checking percentage to -1 * update code with review comments. Added a SetUp() method in the test and move the sleep to there to make sure this is done every test in a systemactic way --------- Co-authored-by: Richardvdketterij --- diagnostic_common_diagnostics/CMakeLists.txt | 7 +- diagnostic_common_diagnostics/README.md | 32 ++++- .../cpu_monitor.py | 119 ++++++++++++++++++ diagnostic_common_diagnostics/mainpage.dox | 1 + diagnostic_common_diagnostics/package.xml | 6 +- .../test/systemtest/test_cpu_monitor.py | 116 +++++++++++++++++ 6 files changed, 271 insertions(+), 10 deletions(-) create mode 100755 diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py create mode 100644 diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py diff --git a/diagnostic_common_diagnostics/CMakeLists.txt b/diagnostic_common_diagnostics/CMakeLists.txt index 65720a08..5c0f11f6 100644 --- a/diagnostic_common_diagnostics/CMakeLists.txt +++ b/diagnostic_common_diagnostics/CMakeLists.txt @@ -8,6 +8,7 @@ find_package(ament_cmake_python REQUIRED) ament_python_install_package(${PROJECT_NAME}) install(PROGRAMS + ${PROJECT_NAME}/cpu_monitor.py ${PROJECT_NAME}/ntp_monitor.py DESTINATION lib/${PROJECT_NAME} ) @@ -17,10 +18,14 @@ if(BUILD_TESTING) ament_lint_auto_find_test_dependencies() find_package(ament_cmake_pytest REQUIRED) + ament_add_pytest_test( + 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) endif() -ament_package() \ No newline at end of file +ament_package() diff --git a/diagnostic_common_diagnostics/README.md b/diagnostic_common_diagnostics/README.md index 452d163e..42df1c8d 100644 --- a/diagnostic_common_diagnostics/README.md +++ b/diagnostic_common_diagnostics/README.md @@ -7,8 +7,31 @@ Currently only the NTP monitor is ported to ROS2. # Nodes +## cpu_monitor.py +The `cpu_monitor` module allows users to monitor the CPU usage of their system in real-time. +It publishes the usage percentage in a diagnostic message. + +* Name of the node is "cpu_monitor_" + hostname. +* Uses the following args: + * warning_percentage: If the CPU usage is > warning_percentage, a WARN status will be publised. + * window: the maximum length of the used collections.deque for queuing CPU readings. + +### Published Topics +#### /diagnostics +diagnostic_msgs/DiagnosticArray +The diagnostics information. + +### Parameters +#### warning_percentage +(default: 90) +warning percentage threshold. + +#### window +(default: 1) +Length of CPU readings queue. + ## ntp_monitor.py -Runs 'ntpdate' to check if the system clock is synchronized with the NTP server. +Runs 'ntpdate' to check if the system clock is synchronized with the NTP server. * If the offset is smaller than `offset-tolerance`, an `OK` status will be published. * If the offset is larger than the configured `offset-tolerance`, a `WARN` status will be published, * if it is bigger than `error-offset-tolerance`, an `ERROR` status will be published. @@ -20,7 +43,7 @@ diagnostic_msgs/DiagnosticArray The diagnostics information. ### Parameters -#### ntp_hostname +#### ntp_hostname (default: "pool.ntp.org") Hostname of NTP server. @@ -46,9 +69,6 @@ Disable self test. ## hd_monitor.py **To be ported** -## cpu_monitor.py -**To be ported** - ## ram_monitor.py **To be ported** @@ -56,4 +76,4 @@ Disable self test. **To be ported** ## tf_monitor.py -**To be ported** \ No newline at end of file +**To be ported** diff --git a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py new file mode 100755 index 00000000..86662957 --- /dev/null +++ b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py @@ -0,0 +1,119 @@ +#!/usr/bin/env python3 +# -*- coding: utf-8 -*- +# +# Software License Agreement (BSD License) +# +# Copyright (c) 2017, TNO IVS, Helmond, Netherlands +# 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 TNO IVS 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. + +# \author Rein Appeldoorn + +from collections import deque +import socket +import traceback + +from diagnostic_msgs.msg import DiagnosticStatus + +from diagnostic_updater import DiagnosticTask, Updater + +import psutil + +import rclpy +from rclpy.node import Node + + +class CpuTask(DiagnosticTask): + + def __init__(self, warning_percentage=90, window=1): + DiagnosticTask.__init__(self, 'CPU Information') + + self._warning_percentage = int(warning_percentage) + self._readings = deque(maxlen=window) + + def _get_average_reading(self): + def avg(lst): + return float(sum(lst)) / len(lst) if lst else float('nan') + + return [avg(cpu_percentages) + for cpu_percentages in zip(*self._readings)] + + def run(self, stat): + self._readings.append(psutil.cpu_percent(percpu=True)) + cpu_percentages = self._get_average_reading() + cpu_average = sum(cpu_percentages) / len(cpu_percentages) + + stat.add('CPU Load Average', f'{cpu_average:.2f}') + + warn = False + for idx, cpu_percentage in enumerate(cpu_percentages): + stat.add(f'CPU {idx} Load', f'{cpu_percentage:.2f}') + if cpu_percentage > self._warning_percentage: + warn = True + + if warn: + stat.summary(DiagnosticStatus.WARN, + f'At least one CPU exceeds {self._warning_percentage} percent') + else: + stat.summary(DiagnosticStatus.OK, + f'CPU Average {cpu_average:.2f} percent') + + return stat + + +def main(args=None): + rclpy.init(args=args) + + # Create the node + hostname = socket.gethostname() + node = Node(f'cpu_monitor_{hostname.replace("-", "_")}') + + # Declare and get parameters + node.declare_parameter('warning_percentage', 90) + node.declare_parameter('window', 1) + + warning_percentage = node.get_parameter( + 'warning_percentage').get_parameter_value().integer_value + window = node.get_parameter('window').get_parameter_value().integer_value + + # Create diagnostic updater with default updater rate of 1 hz + updater = Updater(node) + updater.setHardwareID(hostname) + updater.add(CpuTask(warning_percentage=warning_percentage, window=window)) + + rclpy.spin(node) + + +if __name__ == '__main__': + try: + main() + except KeyboardInterrupt: + pass + except Exception: + traceback.print_exc() diff --git a/diagnostic_common_diagnostics/mainpage.dox b/diagnostic_common_diagnostics/mainpage.dox index 25ee9c86..7aa872ce 100644 --- a/diagnostic_common_diagnostics/mainpage.dox +++ b/diagnostic_common_diagnostics/mainpage.dox @@ -4,6 +4,7 @@ \b diagnostic_common_diagnostics contains a few common diagnostic nodes +- cpu_monitor publishes diagnostic messages with the CPU usage of the system. - ntp_monitor publishes diagnostic messages for how well the NTP time sync is working. - tf_monitor used to publish diagnostic messages reporting on the health of the TF tree. It is based on tfwtf. It is not ported to ROS2. diff --git a/diagnostic_common_diagnostics/package.xml b/diagnostic_common_diagnostics/package.xml index 9d50bbe3..f6bad920 100644 --- a/diagnostic_common_diagnostics/package.xml +++ b/diagnostic_common_diagnostics/package.xml @@ -18,20 +18,20 @@ ament_cmake ament_cmake_python - rclpy diagnostic_updater python3-ntplib + python3-psutil ament_lint_auto ament_cmake_xmllint ament_cmake_lint_cmake - + ament_cmake_pytest diff --git a/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py b/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py new file mode 100644 index 00000000..28430c48 --- /dev/null +++ b/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py @@ -0,0 +1,116 @@ +# -*- 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 time +import unittest + +from diagnostic_common_diagnostics.cpu_monitor import CpuTask + +from diagnostic_msgs.msg import DiagnosticStatus + +from diagnostic_updater import DiagnosticArray, Updater +from diagnostic_updater import DiagnosticStatusWrapper + +import rclpy +from rclpy.node import Node + + +class TestCPUMonitor(unittest.TestCase): + + @classmethod + def setUpClass(cls): + rclpy.init(args=None) + + @classmethod + def tearDownClass(cls): + if rclpy.ok(): + rclpy.shutdown() + + def setUp(self): + # In this case is recommended for accuracy that psutil.cpu_percent() + # function be called with at least 0.1 seconds between calls. + time.sleep(0.1) + + def diagnostics_callback(self, msg): + self.message_recieved = True + self.assertEqual(len(msg.status), 1) + + def test_ok(self): + warning_percentage = 100 + task = CpuTask(warning_percentage) + stat = DiagnosticStatusWrapper() + task.run(stat) + self.assertEqual(task.name, 'CPU Information') + self.assertEqual(stat.level, DiagnosticStatus.OK) + self.assertIn(str('CPU Average'), stat.message) + + # Check for at least 1 CPU Load Average and 1 CPU Load + self.assertGreaterEqual(len(stat.values), 2) + + def test_warn(self): + warning_percentage = -1 + task = CpuTask(warning_percentage) + stat = DiagnosticStatusWrapper() + task.run(stat) + print(f'Raw readings: {task._readings}') + self.assertEqual(task.name, 'CPU Information') + self.assertEqual(stat.level, DiagnosticStatus.WARN) + self.assertIn(str('At least one CPU exceeds'), stat.message) + + # Check for at least 1 CPU Load Average and 1 CPU Load + self.assertGreaterEqual(len(stat.values), 2) + + def test_updater(self): + self.message_recieved = False + + node = Node('cpu_monitor_test') + updater = Updater(node) + updater.setHardwareID('test_id') + updater.add(CpuTask()) + + node.create_subscription( + DiagnosticArray, '/diagnostics', self.diagnostics_callback, 10) + + start_time = time.time() + timeout = 5.0 # Timeout in seconds + + while not self.message_recieved: + rclpy.spin_once(node) + time.sleep(0.1) + elapsed_time = time.time() - start_time + if elapsed_time >= timeout: + self.fail('No diagnostics received') + + +if __name__ == '__main__': + unittest.main() From 83c030e02514c185c91cea4b63da662566cb7039 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Fri, 22 Mar 2024 13:56:40 +0100 Subject: [PATCH 3/7] Rolling obviously also uses the jazzy branch Signed-off-by: Christian Henkel --- README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 70032ebf..96c20ae5 100644 --- a/README.md +++ b/README.md @@ -37,12 +37,12 @@ Diagnostics messages that are not aggregated can be visualized by [`rqt_runtime_ The [`ros2` branch](https://github.com/ros/diagnostics/tree/ros2) targets - *Humble Hawksbill* -- *Iron Irwini* and -- *Rolling Ridley* +- *Iron Irwini* The [`ros2-jazzy` branch](https://github.com/ros/diagnostics/tree/ros2-jazzy) targets - *Jazzy Jalisco* +- *Rolling Ridley* # License From 07ed478a65a6b94bdf5419d41f6ee9c5a102a8d1 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Fri, 22 Mar 2024 14:16:26 +0100 Subject: [PATCH 4/7] changelogs Signed-off-by: Christian Henkel --- diagnostic_aggregator/CHANGELOG.rst | 10 ++++++++++ diagnostic_common_diagnostics/CHANGELOG.rst | 8 ++++++++ diagnostic_updater/CHANGELOG.rst | 9 +++++++++ diagnostics/CHANGELOG.rst | 3 +++ self_test/CHANGELOG.rst | 5 +++++ 5 files changed, 35 insertions(+) diff --git a/diagnostic_aggregator/CHANGELOG.rst b/diagnostic_aggregator/CHANGELOG.rst index 9c48d2f1..8cf482f6 100644 --- a/diagnostic_aggregator/CHANGELOG.rst +++ b/diagnostic_aggregator/CHANGELOG.rst @@ -2,6 +2,16 @@ Changelog for package diagnostic_aggregator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Avoid rolling up an ERROR state when empty GenericAnalyzer blocks are marked discard_stale, or when all of their items are STALE. (`#315 `_) +* formatting fixes from PR324 (`#327 `_) +* Debugging instability introduced by `#317 `_ (`#323 `_) +* feat: publish top level msg when error is received (`#317 `_) +* Empty default aggregator base_path (`#305 `_) +* using defined state for stale (`#298 `_) +* Contributors: Andrew Symington, Christian Henkel, outrider-jhulas + 3.1.2 (2023-03-24) ------------------ diff --git a/diagnostic_common_diagnostics/CHANGELOG.rst b/diagnostic_common_diagnostics/CHANGELOG.rst index 506989c6..958b0145 100644 --- a/diagnostic_common_diagnostics/CHANGELOG.rst +++ b/diagnostic_common_diagnostics/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package diagnostic_common_diagnostics ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Port cpu_monitor to ROS2 (`#326 `_) +* Debugging instability introduced by `#317 `_ (`#323 `_) +* not testing on foxy any more (`#310 `_) +* Iron support (`#304 `_) +* Contributors: Christian Henkel, Richard + 3.1.2 (2023-03-24) ------------------ * replacing ntpdate with ntplib (`#289 `_) diff --git a/diagnostic_updater/CHANGELOG.rst b/diagnostic_updater/CHANGELOG.rst index a4e69216..f85ecba4 100644 --- a/diagnostic_updater/CHANGELOG.rst +++ b/diagnostic_updater/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package diagnostic_updater ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* including depdency (`#322 `_) +* Debugging instability introduced by `#317 `_ (`#323 `_) +* feat: add param to use fqn in updater (`#320 `_) +* fix: method names & verbose logging (`#307 `_) +* Fix diagnostic_updater timestamps (`#299 `_) +* Contributors: Christian Henkel, Kevin Schwarzer, h-wata, outrider-jhulas + 3.1.2 (2023-03-24) ------------------ diff --git a/diagnostics/CHANGELOG.rst b/diagnostics/CHANGELOG.rst index 9e45ec83..992fbc2f 100644 --- a/diagnostics/CHANGELOG.rst +++ b/diagnostics/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package diagnostics ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 3.1.2 (2023-03-24) ------------------ diff --git a/self_test/CHANGELOG.rst b/self_test/CHANGELOG.rst index fe0c3e22..ed277998 100644 --- a/self_test/CHANGELOG.rst +++ b/self_test/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package self_test ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Self test publishes the service under the node name, again (`#269 `_) +* Contributors: Christian Henkel + 3.1.2 (2023-03-24) ------------------ From c1b908cd83554a930d9076560041a8b1173252e9 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Fri, 22 Mar 2024 15:18:21 +0100 Subject: [PATCH 5/7] 3.2.0 --- diagnostic_aggregator/CHANGELOG.rst | 4 ++-- diagnostic_aggregator/package.xml | 2 +- diagnostic_common_diagnostics/CHANGELOG.rst | 4 ++-- diagnostic_common_diagnostics/package.xml | 2 +- diagnostic_updater/CHANGELOG.rst | 4 ++-- diagnostic_updater/package.xml | 2 +- diagnostics/CHANGELOG.rst | 4 ++-- diagnostics/package.xml | 2 +- self_test/CHANGELOG.rst | 4 ++-- self_test/package.xml | 2 +- 10 files changed, 15 insertions(+), 15 deletions(-) diff --git a/diagnostic_aggregator/CHANGELOG.rst b/diagnostic_aggregator/CHANGELOG.rst index 8cf482f6..efda16d0 100644 --- a/diagnostic_aggregator/CHANGELOG.rst +++ b/diagnostic_aggregator/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package diagnostic_aggregator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +3.2.0 (2024-03-22) +------------------ * Avoid rolling up an ERROR state when empty GenericAnalyzer blocks are marked discard_stale, or when all of their items are STALE. (`#315 `_) * formatting fixes from PR324 (`#327 `_) * Debugging instability introduced by `#317 `_ (`#323 `_) diff --git a/diagnostic_aggregator/package.xml b/diagnostic_aggregator/package.xml index 4e0b89a3..677e0436 100644 --- a/diagnostic_aggregator/package.xml +++ b/diagnostic_aggregator/package.xml @@ -2,7 +2,7 @@ diagnostic_aggregator - 3.1.2 + 3.2.0 diagnostic_aggregator Austin Hendrix Brice Rebsamen diff --git a/diagnostic_common_diagnostics/CHANGELOG.rst b/diagnostic_common_diagnostics/CHANGELOG.rst index 958b0145..0c53e9ca 100644 --- a/diagnostic_common_diagnostics/CHANGELOG.rst +++ b/diagnostic_common_diagnostics/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package diagnostic_common_diagnostics ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +3.2.0 (2024-03-22) +------------------ * Port cpu_monitor to ROS2 (`#326 `_) * Debugging instability introduced by `#317 `_ (`#323 `_) * not testing on foxy any more (`#310 `_) diff --git a/diagnostic_common_diagnostics/package.xml b/diagnostic_common_diagnostics/package.xml index f6bad920..de8808d7 100644 --- a/diagnostic_common_diagnostics/package.xml +++ b/diagnostic_common_diagnostics/package.xml @@ -2,7 +2,7 @@ diagnostic_common_diagnostics - 3.1.2 + 3.2.0 diagnostic_common_diagnostics Austin Hendrix Brice Rebsamen diff --git a/diagnostic_updater/CHANGELOG.rst b/diagnostic_updater/CHANGELOG.rst index f85ecba4..e5d4da06 100644 --- a/diagnostic_updater/CHANGELOG.rst +++ b/diagnostic_updater/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package diagnostic_updater ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +3.2.0 (2024-03-22) +------------------ * including depdency (`#322 `_) * Debugging instability introduced by `#317 `_ (`#323 `_) * feat: add param to use fqn in updater (`#320 `_) diff --git a/diagnostic_updater/package.xml b/diagnostic_updater/package.xml index c84dca98..6935d9ac 100644 --- a/diagnostic_updater/package.xml +++ b/diagnostic_updater/package.xml @@ -2,7 +2,7 @@ diagnostic_updater - 3.1.2 + 3.2.0 diagnostic_updater contains tools for easily updating diagnostics. it is commonly used in device drivers to keep track of the status of output topics, device status, etc. Austin Hendrix Brice Rebsamen diff --git a/diagnostics/CHANGELOG.rst b/diagnostics/CHANGELOG.rst index 992fbc2f..1f73b133 100644 --- a/diagnostics/CHANGELOG.rst +++ b/diagnostics/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package diagnostics ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +3.2.0 (2024-03-22) +------------------ 3.1.2 (2023-03-24) ------------------ diff --git a/diagnostics/package.xml b/diagnostics/package.xml index c581103e..9445c1f9 100644 --- a/diagnostics/package.xml +++ b/diagnostics/package.xml @@ -2,7 +2,7 @@ diagnostics - 3.1.2 + 3.2.0 diagnostics Austin Hendrix Brice Rebsamen diff --git a/self_test/CHANGELOG.rst b/self_test/CHANGELOG.rst index ed277998..1ebff1e4 100644 --- a/self_test/CHANGELOG.rst +++ b/self_test/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package self_test ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +3.2.0 (2024-03-22) +------------------ * Self test publishes the service under the node name, again (`#269 `_) * Contributors: Christian Henkel diff --git a/self_test/package.xml b/self_test/package.xml index 600cc9cd..6667d9b8 100644 --- a/self_test/package.xml +++ b/self_test/package.xml @@ -2,7 +2,7 @@ self_test - 3.1.2 + 3.2.0 self_test Austin Hendrix Brice Rebsamen From 50770166eb7f5cead0687239d5c84f4712c2683f Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Fri, 22 Mar 2024 16:40:45 +0100 Subject: [PATCH 6/7] 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 2fe97d37..407b1ddb 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -31,7 +31,7 @@ jobs: os: ubuntu-22.04 runs-on: ${{ 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 194753aa87ef2998bd1d65927e5a9ebf46534c21 Mon Sep 17 00:00:00 2001 From: Christian Henkel Date: Fri, 22 Mar 2024 16:42:59 +0100 Subject: [PATCH 7/7] Revert "trying fix" This reverts commit 50770166eb7f5cead0687239d5c84f4712c2683f. --- .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 407b1ddb..2fe97d37 100644 --- a/.github/workflows/test.yaml +++ b/.github/workflows/test.yaml @@ -31,7 +31,7 @@ jobs: os: ubuntu-22.04 runs-on: ${{ matrix.os }} steps: - - uses: ct2034/setup-ros@patch-1 + - uses: ros-tooling/setup-ros@master - run: | sudo pip install pydocstyle==6.1.1 # downgrade to fix https://github.com/ament/ament_lint/pull/428 sudo pip install pip --upgrade