Skip to content

Commit 05a9645

Browse files
authored
Port hd_monitor to ROS2 (#334)
* Port hd_monitor.py * Adapt documentation and CMakeList to new hd_monitor.py * Fix execution flag of hd_monitor * Add launch test for hd_monitor * Implement low and crit parameters in hd_monitor * Improve hd_monitor code quality
1 parent 0af0de1 commit 05a9645

File tree

5 files changed

+283
-1
lines changed

5 files changed

+283
-1
lines changed

diagnostic_common_diagnostics/CMakeLists.txt

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@ install(PROGRAMS
1212
${PROJECT_NAME}/ntp_monitor.py
1313
${PROJECT_NAME}/ram_monitor.py
1414
${PROJECT_NAME}/sensors_monitor.py
15+
${PROJECT_NAME}/hd_monitor.py
1516
DESTINATION lib/${PROJECT_NAME}
1617
)
1718

@@ -29,6 +30,10 @@ if(BUILD_TESTING)
2930
test/systemtest/test_ntp_monitor_launchtest.py
3031
TARGET ntp_monitor_launchtest
3132
TIMEOUT 20)
33+
add_launch_test(
34+
test/systemtest/test_hd_monitor_launchtest.py
35+
TARGET hd_monitor_launchtest
36+
TIMEOUT 20)
3237
endif()
3338

3439
ament_package()

diagnostic_common_diagnostics/README.md

Lines changed: 14 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,20 @@ Computer name in diagnostics output (ex: 'c1')
6767
Disable self test.
6868

6969
## hd_monitor.py
70-
**To be ported**
70+
Runs 'shutil.disk_usage' to check if there is enough space left on a given device.
71+
* Above 5% of free space left, an `OK` status will be published.
72+
* Between 5% and 1%, a `WARN` status will be published,
73+
* Below 1%, an `ERROR` status will be published.
74+
75+
### Published Topics
76+
#### /diagnostics
77+
diagnostic_msgs/DiagnosticArray
78+
The diagnostics information.
79+
80+
### Parameters
81+
#### path
82+
(default: home directory "~")
83+
Path in which to check remaining space.
7184

7285
## ram_monitor.py
7386
The `ram_monitor` module allows users to monitor the RAM usage of their system in real-time.
Lines changed: 153 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,153 @@
1+
#! /usr/bin/env python3
2+
"""Hard Drive (or any other memory) monitor. Contains a the monitor node and its main function."""
3+
# -*- coding: utf-8 -*-
4+
#
5+
# Software License Agreement (BSD License)
6+
#
7+
# Copyright (c) 2009, Willow Garage, Inc.
8+
# All rights reserved.
9+
#
10+
# Redistribution and use in source and binary forms, with or without
11+
# modification, are permitted provided that the following conditions
12+
# are met:
13+
#
14+
# * Redistributions of source code must retain the above copyright
15+
# notice, this list of conditions and the following disclaimer.
16+
# * Redistributions in binary form must reproduce the above
17+
# copyright notice, this list of conditions and the following
18+
# disclaimer in the documentation and/or other materials provided
19+
# with the distribution.
20+
# * Neither the name of the Willow Garage nor the names of its
21+
# contributors may be used to endorse or promote products derived
22+
# from this software without specific prior written permission.
23+
#
24+
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25+
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26+
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27+
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28+
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29+
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30+
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31+
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32+
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33+
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34+
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35+
# POSSIBILITY OF SUCH DAMAGE.
36+
37+
# \author Kevin Watts
38+
# \author Antoine Lima
39+
40+
from pathlib import Path
41+
from shutil import disk_usage
42+
from socket import gethostname
43+
from typing import List
44+
45+
from diagnostic_msgs.msg import DiagnosticStatus, KeyValue
46+
from diagnostic_updater import Updater
47+
from rcl_interfaces.msg import SetParametersResult
48+
import rclpy
49+
from rclpy.node import Node
50+
51+
52+
FREE_PERCENT_LOW = 0.05
53+
FREE_PERCENT_CRIT = 0.01
54+
DICT_STATUS = {
55+
DiagnosticStatus.OK: 'OK',
56+
DiagnosticStatus.WARN: 'Warning',
57+
DiagnosticStatus.ERROR: 'Error',
58+
}
59+
DICT_USAGE = {
60+
DiagnosticStatus.OK: 'OK',
61+
DiagnosticStatus.WARN: 'Low Disk Space',
62+
DiagnosticStatus.ERROR: 'Very Low Disk Space',
63+
}
64+
65+
66+
class HDMonitor(Node):
67+
"""Diagnostic node checking the remaining space on the specified hard drive.
68+
69+
Three ROS parameters:
70+
- path: Path on the filesystem to check (string, default: home directory)
71+
- free_percent_low: Percentage at which to consider the space left as low
72+
- free_percent_crit: Percentage at which to consider the space left as critical
73+
"""
74+
75+
def __init__(self):
76+
hostname = gethostname().replace('.', '_').replace('-', '_')
77+
super().__init__(f'hd_monitor_{hostname}')
78+
79+
self._path = '~'
80+
self._free_percent_low = 0.05
81+
self._free_percent_crit = 0.01
82+
83+
self.add_on_set_parameters_callback(self.callback_config)
84+
self.declare_parameter('path', self._path)
85+
self.declare_parameter('free_percent_low', self._free_percent_low)
86+
self.declare_parameter('free_percent_crit', self._free_percent_crit)
87+
88+
self._updater = Updater(self)
89+
self._updater.setHardwareID(hostname)
90+
self._updater.add(f'{hostname} HD Usage', self.check_disk_usage)
91+
92+
def callback_config(self, params: List[rclpy.Parameter]):
93+
"""Retrieve ROS parameters.
94+
95+
see the class documentation for declared parameters.
96+
"""
97+
for param in params:
98+
match param.name:
99+
case 'path':
100+
self._path = str(
101+
Path(param.value).expanduser().resolve(strict=True)
102+
)
103+
case 'free_percent_low':
104+
self._free_percent_low = param.value
105+
case 'free_percent_crit':
106+
self._free_percent_crit = param.value
107+
108+
return SetParametersResult(successful=True)
109+
110+
def check_disk_usage(self, diag: DiagnosticStatus) -> DiagnosticStatus:
111+
"""Compute the disk usage and derive a status from it.
112+
113+
Task periodically ran by the diagnostic updater.
114+
"""
115+
diag.level = DiagnosticStatus.OK
116+
117+
total, _, free = disk_usage(self._path)
118+
percent = free / total
119+
120+
if percent > self._free_percent_low:
121+
diag.level = DiagnosticStatus.OK
122+
elif percent > self._free_percent_crit:
123+
diag.level = DiagnosticStatus.WARN
124+
else:
125+
diag.level = DiagnosticStatus.ERROR
126+
127+
total_go = total // (1024 * 1024)
128+
diag.values.extend(
129+
[
130+
KeyValue(key='Name', value=self._path),
131+
KeyValue(key='Status', value=DICT_STATUS[diag.level]),
132+
KeyValue(key='Total (Go)', value=str(total_go)),
133+
KeyValue(key='Available (%)', value=str(round(percent, 2))),
134+
]
135+
)
136+
137+
diag.message = DICT_USAGE[diag.level]
138+
return diag
139+
140+
141+
def main(args=None):
142+
"""Run the HDMonitor class."""
143+
rclpy.init(args=args)
144+
145+
node = HDMonitor()
146+
try:
147+
rclpy.spin(node)
148+
except KeyboardInterrupt:
149+
pass
150+
151+
152+
if __name__ == '__main__':
153+
main()

diagnostic_common_diagnostics/mainpage.dox

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@
55
\b diagnostic_common_diagnostics contains a few common diagnostic nodes
66

77
- cpu_monitor publishes diagnostic messages with the CPU usage of the system.
8+
- hd_monitor publishes diagnostic messages related to the available space on a given storage device.
89
- ntp_monitor publishes diagnostic messages for how well the NTP time sync is working.
910
- tf_monitor used to publish diagnostic messages reporting on the health of
1011
the TF tree. It is based on tfwtf. It is not ported to ROS2.
Lines changed: 110 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,110 @@
1+
#!/usr/bin/env python3
2+
# -*- coding: utf-8 -*-
3+
# Software License Agreement (BSD License)
4+
#
5+
# Copyright (c) 2023, Robert Bosch GmbH
6+
# All rights reserved.
7+
#
8+
# Redistribution and use in source and binary forms, with or without
9+
# modification, are permitted provided that the following conditions
10+
# are met:
11+
#
12+
# * Redistributions of source code must retain the above copyright
13+
# notice, this list of conditions and the following disclaimer.
14+
# * Redistributions in binary form must reproduce the above
15+
# copyright notice, this list of conditions and the following
16+
# disclaimer in the documentation and/or other materials provided
17+
# with the distribution.
18+
# * Neither the name of the Willow Garage nor the names of its
19+
# contributors may be used to endorse or promote products derived
20+
# from this software without specific prior written permission.
21+
#
22+
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23+
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24+
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25+
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26+
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27+
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28+
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29+
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30+
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31+
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32+
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33+
# POSSIBILITY OF SUCH DAMAGE.
34+
35+
import unittest
36+
37+
from diagnostic_msgs.msg import DiagnosticArray
38+
39+
import launch
40+
41+
import launch_ros
42+
43+
import launch_testing
44+
45+
from launch_testing_ros import WaitForTopics
46+
47+
import pytest
48+
49+
import rclpy
50+
51+
52+
@pytest.mark.launch_test
53+
def generate_test_description():
54+
"""Launch the hd_monitor node and return a launch description."""
55+
return launch.LaunchDescription(
56+
[
57+
launch_ros.actions.Node(
58+
package='diagnostic_common_diagnostics',
59+
executable='hd_monitor.py',
60+
name='hd_monitor',
61+
output='screen',
62+
parameters=[{'free_percent_low': 0.20, 'free_percent_crit': 0.05}],
63+
),
64+
launch_testing.actions.ReadyToTest(),
65+
]
66+
)
67+
68+
69+
class TestHDMonitor(unittest.TestCase):
70+
"""Test if the hd_monitor node is publishing diagnostics."""
71+
72+
def __init__(self, methodName: str = 'runTest') -> None:
73+
super().__init__(methodName)
74+
self.received_messages = []
75+
76+
def _received_message(self, msg):
77+
self.received_messages.append(msg)
78+
79+
def _get_min_level(self):
80+
levels = [
81+
int.from_bytes(status.level, 'little')
82+
for diag in self.received_messages
83+
for status in diag.status
84+
]
85+
if len(levels) == 0:
86+
return -1
87+
return min(levels)
88+
89+
def test_topic_published(self):
90+
"""Test if the hd_monitor node is publishing diagnostics."""
91+
with WaitForTopics([('/diagnostics', DiagnosticArray)], timeout=5):
92+
print('Topic found')
93+
94+
rclpy.init()
95+
test_node = rclpy.create_node('test_node')
96+
test_node.create_subscription(
97+
DiagnosticArray, '/diagnostics', self._received_message, 1
98+
)
99+
100+
while len(self.received_messages) < 10:
101+
rclpy.spin_once(test_node, timeout_sec=1)
102+
if (min_level := self._get_min_level()) == 0:
103+
break
104+
105+
test_node.destroy_node()
106+
rclpy.shutdown()
107+
print(f'Got {len(self.received_messages)} messages:')
108+
for msg in self.received_messages:
109+
print(msg)
110+
self.assertEqual(min_level, 0)

0 commit comments

Comments
 (0)