|
| 1 | +#!/usr/bin/env python3 |
| 2 | + |
| 3 | +# Copyright 2024 The Autoware Contributors |
| 4 | +# |
| 5 | +# Licensed under the Apache License, Version 2.0 (the "License"); |
| 6 | +# you may not use this file except in compliance with the License. |
| 7 | +# You may obtain a copy of the License at |
| 8 | +# |
| 9 | +# http://www.apache.org/licenses/LICENSE-2.0 |
| 10 | +# |
| 11 | +# Unless required by applicable law or agreed to in writing, software |
| 12 | +# distributed under the License is distributed on an "AS IS" BASIS, |
| 13 | +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 14 | +# See the License for the specific language governing permissions and |
| 15 | +# limitations under the License. |
| 16 | + |
| 17 | +import argparse |
| 18 | + |
| 19 | +from diagnostic_msgs.msg import DiagnosticStatus |
| 20 | +import rclpy |
| 21 | +import rclpy.node |
| 22 | +from tier4_system_msgs.msg import DiagnosticGraph |
| 23 | + |
| 24 | + |
| 25 | +def print_table(lines: list, header: list): |
| 26 | + widths = [0 for _ in range(len(header))] |
| 27 | + lines.insert(0, header) |
| 28 | + for line in lines: |
| 29 | + widths = map(max, widths, map(len, line)) |
| 30 | + widths = list(widths) |
| 31 | + lines.insert(0, ["-" * w for w in widths]) |
| 32 | + lines.insert(2, ["-" * w for w in widths]) |
| 33 | + for line in lines: |
| 34 | + line = map(lambda v, w: f"{v:{w}}", line, widths) |
| 35 | + line = " | ".join(line) |
| 36 | + print(f"| {line} |") |
| 37 | + |
| 38 | + |
| 39 | +def get_level_text(level: int): |
| 40 | + if level == DiagnosticStatus.OK: |
| 41 | + return "OK" |
| 42 | + if level == DiagnosticStatus.WARN: |
| 43 | + return "WARN" |
| 44 | + if level == DiagnosticStatus.ERROR: |
| 45 | + return "ERROR" |
| 46 | + if level == DiagnosticStatus.STALE: |
| 47 | + return "STALE" |
| 48 | + return "-----" |
| 49 | + |
| 50 | + |
| 51 | +class NodeData: |
| 52 | + def __init__(self, index, node): |
| 53 | + self.index = index |
| 54 | + self._node = node |
| 55 | + |
| 56 | + @property |
| 57 | + def level(self): |
| 58 | + return get_level_text(self._node.status.level) |
| 59 | + |
| 60 | + @property |
| 61 | + def name(self): |
| 62 | + return self._node.status.name |
| 63 | + |
| 64 | + @property |
| 65 | + def links(self): |
| 66 | + return " ".join(str(link.index) for link in self._node.links) |
| 67 | + |
| 68 | + @property |
| 69 | + def line(self): |
| 70 | + return [str(self.index), self.level, self.name, self.links] |
| 71 | + |
| 72 | + |
| 73 | +class DumpNode(rclpy.node.Node): |
| 74 | + def __init__(self, args): |
| 75 | + super().__init__("dump_diagnostic_graph") |
| 76 | + self.sub = self.create_subscription(DiagnosticGraph, args.topic, self.callback, 1) |
| 77 | + |
| 78 | + def callback(self, msg): |
| 79 | + nodes = [NodeData(index, node) for index, node in enumerate(msg.nodes)] |
| 80 | + table = [node.line for node in nodes] |
| 81 | + print_table(table, ["index", "level", "name", "links"]) |
| 82 | + |
| 83 | + |
| 84 | +if __name__ == "__main__": |
| 85 | + parser = argparse.ArgumentParser() |
| 86 | + parser.add_argument("--topic", default="/diagnostics_graph") |
| 87 | + parser.add_argument("--order", default="index") |
| 88 | + args, unparsed = parser.parse_known_args() |
| 89 | + |
| 90 | + try: |
| 91 | + rclpy.init(args=unparsed) |
| 92 | + rclpy.spin(DumpNode(args)) |
| 93 | + rclpy.shutdown() |
| 94 | + except KeyboardInterrupt: |
| 95 | + pass |
0 commit comments