From 70475f884345ae556a2e5307d036e8802765aa37 Mon Sep 17 00:00:00 2001 From: Richardvdketterij Date: Mon, 15 Jan 2024 12:56:27 +0100 Subject: [PATCH 1/9] add cpu monitor to the common diagnostics --- diagnostic_common_diagnostics/CMakeLists.txt | 3 +- diagnostic_common_diagnostics/README.md | 18 ++- .../cpu_monitor.py | 118 ++++++++++++++++++ diagnostic_common_diagnostics/mainpage.dox | 1 + 4 files changed, 133 insertions(+), 7 deletions(-) create mode 100755 diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py diff --git a/diagnostic_common_diagnostics/CMakeLists.txt b/diagnostic_common_diagnostics/CMakeLists.txt index 65720a08e..b6683fb77 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} ) @@ -23,4 +24,4 @@ if(BUILD_TESTING) 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 452d163ed..95e416277 100644 --- a/diagnostic_common_diagnostics/README.md +++ b/diagnostic_common_diagnostics/README.md @@ -8,19 +8,28 @@ Currently only the NTP monitor is ported to ROS2. # Nodes ## 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. * If there was an error running `ntpdate`, an `ERROR` status will be published. +## 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 -#### ntp_hostname +#### ntp_hostname (default: "pool.ntp.org") Hostname of NTP server. @@ -46,9 +55,6 @@ Disable self test. ## hd_monitor.py **To be ported** -## cpu_monitor.py -**To be ported** - ## ram_monitor.py **To be ported** @@ -56,4 +62,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 000000000..1bc5fba7d --- /dev/null +++ b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py @@ -0,0 +1,118 @@ +#!/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 + +import collections +import rclpy +import socket +import psutil + +from rclpy.node import Node +from diagnostic_msgs.msg import DiagnosticStatus +from diagnostic_updater import DiagnosticTask, Updater + + +class CpuTask(DiagnosticTask): + def __init__(self, node, hostname, warning_percentage=90, window=1): + DiagnosticTask.__init__(self, "CPU Information") + + self._nh: Node = node + self._warning_percentage = int(warning_percentage) + self._readings = collections.deque(maxlen=window) + + # Create diagnostic updater with default updater rate of 1 hz + self.updater = Updater(self._nh, period=1.0) + self.updater.setHardwareID(hostname) + + # Add task to diagnostic updater with the callback producing the diagnostic messages + self.updater.add(hostname, self.produce_diagnostics) + + 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 produce_diagnostics(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", "{:.2f}".format(cpu_average)) + + warn = False + for idx, val in enumerate(cpu_percentages): + stat.add("CPU {} Load".format(idx), "{:.2f}".format(val)) + if val > self._warning_percentage: + warn = True + + if warn: + stat.summary(DiagnosticStatus.WARN, + "At least one CPU exceeds {:d} percent".format(self._warning_percentage)) + else: + stat.summary(DiagnosticStatus.OK, "CPU Average {:.2f} percent".format(cpu_average)) + + return stat + + +def main(args=None): + rclpy.init(args=args) + + # Create the node + hostname = socket.gethostname() + node = Node('cpu_monitor_%s' % 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 the CpuTask + CpuTask(node=node, hostname=hostname, warning_percentage=warning_percentage, window=window) + + rclpy.spin(node) + + +if __name__ == '__main__': + try: + main() + except KeyboardInterrupt: + pass + except Exception: + import traceback + traceback.print_exc() diff --git a/diagnostic_common_diagnostics/mainpage.dox b/diagnostic_common_diagnostics/mainpage.dox index 25ee9c863..f16635ce2 100644 --- a/diagnostic_common_diagnostics/mainpage.dox +++ b/diagnostic_common_diagnostics/mainpage.dox @@ -5,6 +5,7 @@ \b diagnostic_common_diagnostics contains a few common diagnostic nodes - ntp_monitor publishes diagnostic messages for how well the NTP time sync is working. +- cpu_monitor publishes diagnostic messages with the CPU usage of the system. - 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. From c13e96acce17225aa53a52e8ad9201bb916a02d6 Mon Sep 17 00:00:00 2001 From: Richardvdketterij Date: Mon, 15 Jan 2024 16:39:43 +0100 Subject: [PATCH 2/9] change CpuTask back to DiagnosticTask --- diagnostic_common_diagnostics/CMakeLists.txt | 4 + .../cpu_monitor.py | 18 ++--- .../test/systemtest/test_cpu_monitor.py | 73 +++++++++++++++++++ 3 files changed, 83 insertions(+), 12 deletions(-) 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 b6683fb77..43202b9e0 100644 --- a/diagnostic_common_diagnostics/CMakeLists.txt +++ b/diagnostic_common_diagnostics/CMakeLists.txt @@ -22,6 +22,10 @@ if(BUILD_TESTING) test_ntp_monitor test/systemtest/test_ntp_monitor.py TIMEOUT 10) + ament_add_pytest_test( + test_cpu_monitor + test/systemtest/test_cpu_monitor.py + TIMEOUT 10) endif() ament_package() diff --git a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py index 1bc5fba7d..b22261e9e 100755 --- a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py +++ b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py @@ -46,27 +46,19 @@ class CpuTask(DiagnosticTask): - def __init__(self, node, hostname, warning_percentage=90, window=1): + def __init__(self, warning_percentage=90, window=1): DiagnosticTask.__init__(self, "CPU Information") - self._nh: Node = node self._warning_percentage = int(warning_percentage) self._readings = collections.deque(maxlen=window) - # Create diagnostic updater with default updater rate of 1 hz - self.updater = Updater(self._nh, period=1.0) - self.updater.setHardwareID(hostname) - - # Add task to diagnostic updater with the callback producing the diagnostic messages - self.updater.add(hostname, self.produce_diagnostics) - 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 produce_diagnostics(self, stat): + 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) @@ -102,8 +94,10 @@ def main(args=None): warning_percentage = node.get_parameter('warning_percentage').get_parameter_value().integer_value window = node.get_parameter('window').get_parameter_value().integer_value - # Create the CpuTask - CpuTask(node=node, hostname=hostname, warning_percentage=warning_percentage, window=window) + # 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) 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 000000000..0e482ff94 --- /dev/null +++ b/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py @@ -0,0 +1,73 @@ +#!/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 unittest +import time +from diagnostic_msgs.msg import DiagnosticStatus +from diagnostic_updater import DiagnosticStatusWrapper +from diagnostic_common_diagnostics.cpu_monitor import CpuTask + +class TestCPUMonitor(unittest.TestCase): + 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): + # time.sleep(0.1) + + warning_percentage2 = 0 + task2 = CpuTask(warning_percentage2) + stat2 = DiagnosticStatusWrapper() + task2.run(stat2) + self.assertEqual(task2.name, 'CPU Information') + self.assertEqual(stat2.level, DiagnosticStatus.WARN) + self.assertIn(str('At least one CPU exceeds'), stat2.message) + + # Check for at least 1 CPU Load Average and 1 CPU Load + self.assertGreaterEqual(len(stat2.values), 2) + # time.sleep(0.25) + + # def test_updater(self): + + +if __name__ == "__main__": + unittest.main() From b12bbdaa0975c9b2657c8b01e3847d63745cb75c Mon Sep 17 00:00:00 2001 From: Richardvdketterij Date: Tue, 16 Jan 2024 09:50:55 +0100 Subject: [PATCH 3/9] add 3 unittests --- .../test/systemtest/test_cpu_monitor.py | 51 +++++++++++++++++-- 1 file changed, 48 insertions(+), 3 deletions(-) diff --git a/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py b/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py index 0e482ff94..bc21c3257 100644 --- a/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py +++ b/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py @@ -34,12 +34,34 @@ import unittest import time +import rclpy + +from rclpy.node import Node from diagnostic_msgs.msg import DiagnosticStatus from diagnostic_updater import DiagnosticStatusWrapper +from diagnostic_updater import DiagnosticArray, Updater from diagnostic_common_diagnostics.cpu_monitor import CpuTask +import time class TestCPUMonitor(unittest.TestCase): + @classmethod + def setUpClass(cls): + rclpy.init(args=None) + + @classmethod + def tearDownClass(cls): + if rclpy.ok(): + rclpy.shutdown() + + def diagnostics_callback(self, msg): + self.message_recieved = True + self.assertEqual(len(msg.status), 1) + def test_ok(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) + warning_percentage = 100 task = CpuTask(warning_percentage) stat = DiagnosticStatusWrapper() @@ -52,7 +74,9 @@ def test_ok(self): self.assertGreaterEqual(len(stat.values), 2) def test_warn(self): - # time.sleep(0.1) + # 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) warning_percentage2 = 0 task2 = CpuTask(warning_percentage2) @@ -64,9 +88,30 @@ def test_warn(self): # Check for at least 1 CPU Load Average and 1 CPU Load self.assertGreaterEqual(len(stat2.values), 2) - # time.sleep(0.25) - # def test_updater(self): + def test_updater(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) + + 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__": From fe86d0f712feeb6ece0ecbbcf5cdd7b18d449d86 Mon Sep 17 00:00:00 2001 From: Richardvdketterij Date: Tue, 16 Jan 2024 13:19:10 +0100 Subject: [PATCH 4/9] flake8 --- .../diagnostic_common_diagnostics/cpu_monitor.py | 11 +++++++---- .../test/systemtest/test_cpu_monitor.py | 14 ++++++++------ 2 files changed, 15 insertions(+), 10 deletions(-) diff --git a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py index b22261e9e..2318e8319 100755 --- a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py +++ b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py @@ -40,9 +40,9 @@ import socket import psutil -from rclpy.node import Node from diagnostic_msgs.msg import DiagnosticStatus from diagnostic_updater import DiagnosticTask, Updater +from rclpy.node import Node class CpuTask(DiagnosticTask): @@ -56,7 +56,8 @@ 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)] + return [avg(cpu_percentages) + for cpu_percentages in zip(*self._readings)] def run(self, stat): self._readings.append(psutil.cpu_percent(percpu=True)) @@ -75,7 +76,8 @@ def run(self, stat): stat.summary(DiagnosticStatus.WARN, "At least one CPU exceeds {:d} percent".format(self._warning_percentage)) else: - stat.summary(DiagnosticStatus.OK, "CPU Average {:.2f} percent".format(cpu_average)) + stat.summary(DiagnosticStatus.OK, + "CPU Average {:.2f} percent".format(cpu_average)) return stat @@ -91,7 +93,8 @@ def main(args=None): node.declare_parameter('warning_percentage', 90) node.declare_parameter('window', 1) - warning_percentage = node.get_parameter('warning_percentage').get_parameter_value().integer_value + 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 diff --git a/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py b/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py index bc21c3257..445f270b9 100644 --- a/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py +++ b/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py @@ -32,16 +32,17 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -import unittest import time -import rclpy +import unittest -from rclpy.node import Node from diagnostic_msgs.msg import DiagnosticStatus -from diagnostic_updater import DiagnosticStatusWrapper from diagnostic_updater import DiagnosticArray, Updater +from diagnostic_updater import DiagnosticStatusWrapper + +import rclpy +from rclpy.node import Node from diagnostic_common_diagnostics.cpu_monitor import CpuTask -import time + class TestCPUMonitor(unittest.TestCase): @classmethod @@ -101,7 +102,8 @@ def test_updater(self): updater.setHardwareID("test_id") updater.add(CpuTask()) - node.create_subscription(DiagnosticArray, '/diagnostics', self.diagnostics_callback, 10) + node.create_subscription( + DiagnosticArray, '/diagnostics', self.diagnostics_callback, 10) start_time = time.time() timeout = 5.0 # Timeout in seconds From 61c7be33c61e0372a19249c664a1ce9d596a5600 Mon Sep 17 00:00:00 2001 From: Richardvdketterij Date: Wed, 17 Jan 2024 09:45:07 +0100 Subject: [PATCH 5/9] fix flake8 --- .../cpu_monitor.py | 25 +++++++++++-------- .../test/systemtest/test_cpu_monitor.py | 12 +++++---- 2 files changed, 21 insertions(+), 16 deletions(-) diff --git a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py index 2318e8319..bc637fe03 100755 --- a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py +++ b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py @@ -36,18 +36,22 @@ # \author Rein Appeldoorn import collections -import rclpy import socket -import psutil +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") + DiagnosticTask.__init__(self, 'CPU Information') self._warning_percentage = int(warning_percentage) self._readings = collections.deque(maxlen=window) @@ -64,20 +68,20 @@ def run(self, stat): cpu_percentages = self._get_average_reading() cpu_average = sum(cpu_percentages) / len(cpu_percentages) - stat.add("CPU Load Average", "{:.2f}".format(cpu_average)) + stat.add('CPU Load Average', '{:.2f}'.format(cpu_average)) warn = False - for idx, val in enumerate(cpu_percentages): - stat.add("CPU {} Load".format(idx), "{:.2f}".format(val)) - if val > self._warning_percentage: + for idx, cpu_percentage in enumerate(cpu_percentages): + stat.add('CPU {} Load'.format(idx), '{:.2f}'.format(cpu_percentage)) + if cpu_percentage > self._warning_percentage: warn = True if warn: stat.summary(DiagnosticStatus.WARN, - "At least one CPU exceeds {:d} percent".format(self._warning_percentage)) + 'At least one CPU exceeds {} percent'.format(self._warning_percentage)) else: stat.summary(DiagnosticStatus.OK, - "CPU Average {:.2f} percent".format(cpu_average)) + 'CPU Average {:.2f} percent'.format(cpu_average)) return stat @@ -87,7 +91,7 @@ def main(args=None): # Create the node hostname = socket.gethostname() - node = Node('cpu_monitor_%s' % hostname.replace("-", "_")) + node = Node('cpu_monitor_%s' % hostname.replace('-', '_')) # Declare and get parameters node.declare_parameter('warning_percentage', 90) @@ -111,5 +115,4 @@ def main(args=None): except KeyboardInterrupt: pass except Exception: - import traceback traceback.print_exc() diff --git a/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py b/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py index 445f270b9..a7f5e71e0 100644 --- a/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py +++ b/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py @@ -1,4 +1,3 @@ -#!/usr/bin/env python3 # -*- coding: utf-8 -*- # Software License Agreement (BSD License) # @@ -35,16 +34,19 @@ 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 -from diagnostic_common_diagnostics.cpu_monitor import CpuTask class TestCPUMonitor(unittest.TestCase): + @classmethod def setUpClass(cls): rclpy.init(args=None) @@ -99,7 +101,7 @@ def test_updater(self): node = Node('cpu_monitor_test') updater = Updater(node) - updater.setHardwareID("test_id") + updater.setHardwareID('test_id') updater.add(CpuTask()) node.create_subscription( @@ -113,8 +115,8 @@ def test_updater(self): time.sleep(0.1) elapsed_time = time.time() - start_time if elapsed_time >= timeout: - self.fail("No diagnostics received") + self.fail('No diagnostics received') -if __name__ == "__main__": +if __name__ == '__main__': unittest.main() From 471f407d67e6bcc8e3b2548f745544acb39f67d7 Mon Sep 17 00:00:00 2001 From: Richardvdketterij Date: Wed, 17 Jan 2024 09:56:16 +0100 Subject: [PATCH 6/9] fix flake8 --- .../diagnostic_common_diagnostics/cpu_monitor.py | 1 + 1 file changed, 1 insertion(+) diff --git a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py index bc637fe03..bab6d52a3 100755 --- a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py +++ b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/cpu_monitor.py @@ -50,6 +50,7 @@ class CpuTask(DiagnosticTask): + def __init__(self, warning_percentage=90, window=1): DiagnosticTask.__init__(self, 'CPU Information') From c093e871273da43f8e76f3dd849948a7e90b7408 Mon Sep 17 00:00:00 2001 From: Richardvdketterij Date: Wed, 17 Jan 2024 10:37:39 +0100 Subject: [PATCH 7/9] add psutil to package xml --- diagnostic_common_diagnostics/package.xml | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/diagnostic_common_diagnostics/package.xml b/diagnostic_common_diagnostics/package.xml index 9d50bbe33..78d837930 100644 --- a/diagnostic_common_diagnostics/package.xml +++ b/diagnostic_common_diagnostics/package.xml @@ -18,21 +18,22 @@ ament_cmake ament_cmake_python - rclpy diagnostic_updater python3-ntplib + python3-psutil + rclpy + ament_cmake_lint_cmake + ament_cmake_pytest + ament_cmake_xmllint ament_lint_auto - ament_cmake_xmllint - ament_cmake_lint_cmake - - ament_cmake_pytest + ament_cmake From 980eb1601c913410cd627cfbbf6e4814efc129e2 Mon Sep 17 00:00:00 2001 From: Richardvdketterij Date: Wed, 17 Jan 2024 10:50:25 +0100 Subject: [PATCH 8/9] add debug print for cpu percentages and change checking percentage to -1 --- .../test/systemtest/test_cpu_monitor.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py b/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py index a7f5e71e0..1c69c923d 100644 --- a/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py +++ b/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py @@ -81,10 +81,11 @@ def test_warn(self): # function be called with at least 0.1 seconds between calls. time.sleep(0.1) - warning_percentage2 = 0 + warning_percentage2 = -1 task2 = CpuTask(warning_percentage2) stat2 = DiagnosticStatusWrapper() task2.run(stat2) + print(f'Raw readings: {task2._readings}') self.assertEqual(task2.name, 'CPU Information') self.assertEqual(stat2.level, DiagnosticStatus.WARN) self.assertIn(str('At least one CPU exceeds'), stat2.message) From f22ab872d22c9c1d03fc3d9a7a779e5247ea1b8e Mon Sep 17 00:00:00 2001 From: Richardvdketterij Date: Wed, 17 Jan 2024 10:51:08 +0100 Subject: [PATCH 9/9] make vars consistant --- .../test/systemtest/test_cpu_monitor.py | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py b/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py index 1c69c923d..6e733692c 100644 --- a/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py +++ b/diagnostic_common_diagnostics/test/systemtest/test_cpu_monitor.py @@ -81,17 +81,17 @@ def test_warn(self): # function be called with at least 0.1 seconds between calls. time.sleep(0.1) - warning_percentage2 = -1 - task2 = CpuTask(warning_percentage2) - stat2 = DiagnosticStatusWrapper() - task2.run(stat2) - print(f'Raw readings: {task2._readings}') - self.assertEqual(task2.name, 'CPU Information') - self.assertEqual(stat2.level, DiagnosticStatus.WARN) - self.assertIn(str('At least one CPU exceeds'), stat2.message) + 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(stat2.values), 2) + self.assertGreaterEqual(len(stat.values), 2) def test_updater(self): # In this case is recommended for accuracy that psutil.cpu_percent()