From 2fe01116db33a9ceb3a405b56e6ae01c37dfe81b Mon Sep 17 00:00:00 2001 From: Antoine Lima Date: Thu, 27 Jun 2024 11:23:31 +0200 Subject: [PATCH] [HD Monitor] Fix pylint errors (import order, docstrings, ...) --- .../hd_monitor.py | 19 ++++++++++++++++--- 1 file changed, 16 insertions(+), 3 deletions(-) diff --git a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/hd_monitor.py b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/hd_monitor.py index 93a9f6ac..505cc7c1 100755 --- a/diagnostic_common_diagnostics/diagnostic_common_diagnostics/hd_monitor.py +++ b/diagnostic_common_diagnostics/diagnostic_common_diagnostics/hd_monitor.py @@ -1,4 +1,5 @@ #! /usr/bin/env python3 +"""Hard Drive (or any other memory) monitor. Contains a the monitor node and its main function.""" # -*- coding: utf-8 -*- # # Software License Agreement (BSD License) @@ -44,8 +45,8 @@ import rclpy from rcl_interfaces.msg import SetParametersResult from rclpy.node import Node -from diagnostic_updater import Updater from diagnostic_msgs.msg import DiagnosticStatus, KeyValue +from diagnostic_updater import Updater FREE_PERCENT_LOW = 0.05 @@ -63,6 +64,13 @@ class HDMonitor(Node): + """Diagnostic node checking the remaining space on the specified hard drive. + + Three ROS parameters: + - path: Path on the filesystem to check (string, default: home directory) + - free_percent_low: Percentage at which to consider the space left as low + - free_percent_crit: Percentage at which to consider the space left as critical + """ def __init__(self): hostname = gethostname().replace(".", "_").replace("-", "_") super().__init__(f"hd_monitor_{hostname}") @@ -71,12 +79,14 @@ def __init__(self): self.declare_parameter("path", "~") self.declare_parameter("free_percent_low", 0.05) self.declare_parameter("free_percent_crit", 0.01) + self._path = self._free_percent_low = self._free_percent_crit = None self._updater = Updater(self) self._updater.setHardwareID(hostname) self._updater.add(f"{hostname} HD Usage", self.check_disk_usage) def callback_config(self, params: List[rclpy.Parameter]): + """Callback for ROS parameters, see the class documentation for declared parameters.""" for param in params: match param.name: case "path": @@ -87,9 +97,11 @@ def callback_config(self, params: List[rclpy.Parameter]): self._free_percent_low = param.value case "free_percent_crit": self._free_percent_crit = param.value + return SetParametersResult(successful=True) def check_disk_usage(self, diag: DiagnosticStatus) -> DiagnosticStatus: + """Task ran regularly by the diagnostic updater that returns the actual status""" diag.level = DiagnosticStatus.OK total, _, free = disk_usage(self._path) @@ -102,12 +114,12 @@ def check_disk_usage(self, diag: DiagnosticStatus) -> DiagnosticStatus: else: diag.level = DiagnosticStatus.ERROR - total_Go = total // (1024 * 1024) + total_go = total // (1024 * 1024) diag.values.extend( [ KeyValue(key="Name", value=self._path), KeyValue(key="Status", value=DICT_STATUS[diag.level]), - KeyValue(key="Total (Go)", value=str(total_Go)), + KeyValue(key="Total (Go)", value=str(total_go)), KeyValue(key="Available (%)", value=str(round(percent, 2))), ] ) @@ -117,6 +129,7 @@ def check_disk_usage(self, diag: DiagnosticStatus) -> DiagnosticStatus: def main(args=None): + """Runs the HDMonitor class""" rclpy.init(args=args) node = HDMonitor()