diff --git a/system/diagnostic_graph_aggregator/CMakeLists.txt b/system/diagnostic_graph_aggregator/CMakeLists.txt index 574978ec5adce..905cc07d81da1 100644 --- a/system/diagnostic_graph_aggregator/CMakeLists.txt +++ b/system/diagnostic_graph_aggregator/CMakeLists.txt @@ -5,32 +5,27 @@ find_package(autoware_cmake REQUIRED) autoware_package() ament_auto_add_library(${PROJECT_NAME} SHARED + src/common/graph/error.cpp + src/common/graph/data.cpp src/common/graph/config.cpp - src/common/graph/debug.cpp + src/common/graph/loader.cpp src/common/graph/graph.cpp src/common/graph/units.cpp ) ament_auto_add_executable(aggregator src/node/aggregator.cpp - src/node/plugin/modes.cpp + src/node/availability.cpp ) target_include_directories(aggregator PRIVATE src/common) -ament_auto_add_executable(converter - src/node/converter.cpp -) -target_include_directories(converter PRIVATE src/common) - ament_auto_add_executable(tree src/tool/tree.cpp - src/tool/utils/loader.cpp ) target_include_directories(tree PRIVATE src/common) ament_auto_add_executable(plantuml src/tool/plantuml.cpp - src/tool/utils/loader.cpp ) target_include_directories(plantuml PRIVATE src/common) @@ -45,10 +40,4 @@ if(BUILD_TESTING) target_include_directories(gtest_${PROJECT_NAME} PRIVATE src/common) endif() -install(PROGRAMS - script/dump.py - RENAME dump - DESTINATION lib/${PROJECT_NAME} -) - ament_auto_package(INSTALL_TO_SHARE config example launch) diff --git a/system/diagnostic_graph_aggregator/README.md b/system/diagnostic_graph_aggregator/README.md index cc49ed88ba98f..c0cd78e0610c2 100644 --- a/system/diagnostic_graph_aggregator/README.md +++ b/system/diagnostic_graph_aggregator/README.md @@ -3,20 +3,25 @@ ## Overview The diagnostic graph aggregator node subscribes to diagnostic array and publishes aggregated diagnostic graph. -As shown in the diagram below, this node introduces extra diagnostic status for intermediate functional unit. -Diagnostic status dependencies will be directed acyclic graph (DAG). +As shown in the diagram below, this node introduces extra diagnostic status for intermediate functional units. ![overview](./doc/overview.drawio.svg) -## Diagnostics graph message +## Diagnostic graph structures -The diagnostics graph that this node outputs is a combination of diagnostic status and connections between them. -This graph consists of an array of diagnostic nodes, and each node has a status and links. -This link contains an index indicating the position of the node in the graph. -Therefore, the graph can be reconstructed from the array of nodes using links. -The following is an example of a message representing the graph in the overview section. +The diagnostic graph is actually a set of fault tree analysis (FTA) for each operation mode of Autoware. +Since the status of the same node may be referenced by multiple nodes, the overall structure is a directed acyclic graph (DAG). +Each node in the diagnostic graph represents the diagnostic status of a specific functional unit, including the input diagnostics. +So we define this as "unit", and call the unit corresponding to the input diagnosis "diag unit" and the others "node unit". -![message](./doc/message.drawio.svg) +Every unit has an error level that is the same as DiagnosticStatus, a unit type, and optionally a unit path. +In addition, every diag unit has a message, a hardware_id, and values that are the same as DiagnosticStatus. +The unit type represents how the unit status is calculated, such as AND or OR. +The unit path is any unique string that represents the functionality of the unit. + +NOTE: This feature is currently under development. +The diagnostic graph also supports "link" because there are cases where connections between units have additional status. +For example, it is natural that many functional units will have an error status until initialization is complete. ## Operation mode availability @@ -34,11 +39,13 @@ This feature breaks the generality of the graph and may be changed to a plugin o ## Interfaces -| Interface Type | Interface Name | Data Type | Description | -| -------------- | ------------------------------------- | ------------------------------------------------- | ------------------ | -| subscription | `/diagnostics` | `diagnostic_msgs/msg/DiagnosticArray` | Diagnostics input. | -| publisher | `/diagnostics_graph` | `tier4_system_msgs/msg/DiagnosticGraph` | Diagnostics graph. | -| publisher | `/system/operation_mode/availability` | `tier4_system_msgs/msg/OperationModeAvailability` | mode availability. | +| Interface Type | Interface Name | Data Type | Description | +| -------------- | ------------------------------------- | ------------------------------------------------- | ---------------------------------- | +| subscription | `/diagnostics` | `diagnostic_msgs/msg/DiagnosticArray` | Diagnostics input. | +| publisher | `/diagnostics_graph/unknowns` | `diagnostic_msgs/msg/DiagnosticArray` | Diagnostics not included in graph. | +| publisher | `/diagnostics_graph/struct` | `tier4_system_msgs/msg/DiagGraphStruct` | Diagnostic graph (static part). | +| publisher | `/diagnostics_graph/status` | `tier4_system_msgs/msg/DiagGraphStatus` | Diagnostic graph (dynamic part). | +| publisher | `/system/operation_mode/availability` | `tier4_system_msgs/msg/OperationModeAvailability` | Operation mode availability. | ## Parameters @@ -49,7 +56,6 @@ This feature breaks the generality of the graph and may be changed to a plugin o | `input_qos_depth` | `uint` | QoS depth of input array topic. | | `graph_qos_depth` | `uint` | QoS depth of output graph topic. | | `use_operation_mode_availability` | `bool` | Use operation mode availability publisher. | -| `use_debug_mode` | `bool` | Use debug output to stdout. | ## Examples @@ -73,13 +79,12 @@ ros2 launch diagnostic_graph_aggregator example-edit.launch.xml ## Debug tools -- [dump](./doc/tool/dump.md) -- [converter](./doc/tool/converter.md) - [tree](./doc/tool/tree.md) +- [diagnostic_graph_utils](../diagnostic_graph_utils/README.md) ## Graph file format - [graph](./doc/format/graph.md) - [path](./doc/format/path.md) -- [node](./doc/format/node.md) +- [unit](./doc/format/unit.md) - [edit](./doc/format/edit.md) diff --git a/system/diagnostic_graph_aggregator/config/default.param.yaml b/system/diagnostic_graph_aggregator/config/default.param.yaml index 2660396bd86df..4fb2303bbd898 100644 --- a/system/diagnostic_graph_aggregator/config/default.param.yaml +++ b/system/diagnostic_graph_aggregator/config/default.param.yaml @@ -1,7 +1,6 @@ /**: ros__parameters: use_operation_mode_availability: true - use_debug_mode: false rate: 10.0 input_qos_depth: 1000 graph_qos_depth: 1 diff --git a/system/diagnostic_graph_aggregator/doc/format/edit/remove.md b/system/diagnostic_graph_aggregator/doc/format/edit/remove.md index 6cd4b25e98828..9a9847e5c6dd3 100644 --- a/system/diagnostic_graph_aggregator/doc/format/edit/remove.md +++ b/system/diagnostic_graph_aggregator/doc/format/edit/remove.md @@ -1,10 +1,10 @@ # Remove -The `remove` object is a edit that removes other nodes. +The `remove` object is a edit that removes other units. ## Format | Name | Type | Required | Description | | ------ | -------- | -------- | ---------------------------------------- | | `type` | `string` | yes | Specify `remove` when using this object. | -| `path` | `string` | yes | The path of the node to remove. | +| `path` | `string` | yes | The path of the unit to remove. | diff --git a/system/diagnostic_graph_aggregator/doc/format/graph.md b/system/diagnostic_graph_aggregator/doc/format/graph.md index 9dace8a2f0e6d..efe85c6e6aaff 100644 --- a/system/diagnostic_graph_aggregator/doc/format/graph.md +++ b/system/diagnostic_graph_aggregator/doc/format/graph.md @@ -7,5 +7,5 @@ The graph object is the top level structure that makes up the configuration file | Name | Type | Required | Description | | ------- | -------------------------------------- | -------- | ------------------------------------------------- | | `files` | list\[[path](./path.md)\] | no | List of path objects for importing subgraphs. | -| `nodes` | list\[[node](./node.md)\] | no | List of node objects that make up the graph. | +| `units` | list\[[unit](./unit.md)\] | no | List of unit objects that make up the graph. | | `edits` | list\[[edit](./edit.md)\] | no | List of edit objects to partially edit the graph. | diff --git a/system/diagnostic_graph_aggregator/doc/format/node/remap.md b/system/diagnostic_graph_aggregator/doc/format/node/remap.md deleted file mode 100644 index abf0d11fae12d..0000000000000 --- a/system/diagnostic_graph_aggregator/doc/format/node/remap.md +++ /dev/null @@ -1,21 +0,0 @@ -# Constant - -!!! warning - - This object is under development. It may be removed in the future. - -The remapping object is a node that converts error levels. - -## Format - -| Name | Type | Required | Description | -| ------ | -------------------------------------- | -------- | ---------------------------------------------------- | -| `type` | `string` | yes | Specify remapping type when using this object. | -| `list` | list\[[node](../node.md)] | yes | List of input node objects. The list size must be 1. | - -## Remapping types - -The supported remapping types are as follows. - -- `warn-to-ok` -- `warn-to-error` diff --git a/system/diagnostic_graph_aggregator/doc/format/node.md b/system/diagnostic_graph_aggregator/doc/format/unit.md similarity index 59% rename from system/diagnostic_graph_aggregator/doc/format/node.md rename to system/diagnostic_graph_aggregator/doc/format/unit.md index 0f4b52b9b8a72..6df4671259f9d 100644 --- a/system/diagnostic_graph_aggregator/doc/format/node.md +++ b/system/diagnostic_graph_aggregator/doc/format/unit.md @@ -1,24 +1,24 @@ -# Node +# Unit -The `node` is a base object that makes up the diagnostic graph. -Any derived object can be used where a node object is required. +The `unit` is a base object that makes up the diagnostic graph. +Any derived object can be used where a unit object is required. ## Format | Name | Type | Required | Description | | ------ | -------- | -------- | ------------------------------------------------- | | `type` | `string` | yes | The string indicating the type of derived object. | -| `path` | `string` | no | Any string to reference from other nodes. | +| `path` | `string` | no | Any string to reference from other units. | ## Derived objects -- [diag](./node/diag.md) -- [and](./node/and.md) -- [or](./node/or.md) -- [remapping](./node/remap.md) +- [diag](./unit/diag.md) +- [and](./unit/and.md) +- [or](./unit/or.md) +- [remapping](./unit/remap.md) - warn-to-ok - warn-to-error -- [constant](./node/const.md) +- [constant](./unit/const.md) - ok - warn - error diff --git a/system/diagnostic_graph_aggregator/doc/format/node/and.md b/system/diagnostic_graph_aggregator/doc/format/unit/and.md similarity index 71% rename from system/diagnostic_graph_aggregator/doc/format/node/and.md rename to system/diagnostic_graph_aggregator/doc/format/unit/and.md index 562018bf0995b..ea14d5101a53c 100644 --- a/system/diagnostic_graph_aggregator/doc/format/node/and.md +++ b/system/diagnostic_graph_aggregator/doc/format/unit/and.md @@ -1,6 +1,6 @@ # And -The `and` object is a node that is evaluated as the maximum error level of the input nodes. +The `and` object is a unit that is evaluated as the maximum error level of the input units. Note that error level `stale` is treated as `error`. ## Format @@ -8,7 +8,7 @@ Note that error level `stale` is treated as `error`. | Name | Type | Required | Description | | ------ | -------------------------------------- | -------- | ------------------------------------------------------------ | | `type` | string | yes | Specify `and` or `short-circuit-and` when using this object. | -| `list` | list\[[node](../node.md)] | yes | List of input node objects. | +| `list` | list\[[unit](../unit.md)] | yes | List of input unit objects. | ## Short-circuit evaluation diff --git a/system/diagnostic_graph_aggregator/doc/format/node/const.md b/system/diagnostic_graph_aggregator/doc/format/unit/const.md similarity index 86% rename from system/diagnostic_graph_aggregator/doc/format/node/const.md rename to system/diagnostic_graph_aggregator/doc/format/unit/const.md index 13495be6cdbda..dac095814a616 100644 --- a/system/diagnostic_graph_aggregator/doc/format/node/const.md +++ b/system/diagnostic_graph_aggregator/doc/format/unit/const.md @@ -1,6 +1,6 @@ # Constant -The constant object is a node with a fixed error level. +The constant object is a unit with a fixed error level. ## Format diff --git a/system/diagnostic_graph_aggregator/doc/format/node/diag.md b/system/diagnostic_graph_aggregator/doc/format/unit/diag.md similarity index 84% rename from system/diagnostic_graph_aggregator/doc/format/node/diag.md rename to system/diagnostic_graph_aggregator/doc/format/unit/diag.md index beba8ed0df5b4..377284322d9a9 100644 --- a/system/diagnostic_graph_aggregator/doc/format/node/diag.md +++ b/system/diagnostic_graph_aggregator/doc/format/unit/diag.md @@ -1,6 +1,6 @@ # Diag -The `diag` object is a node that refers to a specific status within the source diagnostics. +The `diag` object is a unit that refers to a specific status within the source diagnostics. ## Format diff --git a/system/diagnostic_graph_aggregator/doc/format/node/link.md b/system/diagnostic_graph_aggregator/doc/format/unit/link.md similarity index 67% rename from system/diagnostic_graph_aggregator/doc/format/node/link.md rename to system/diagnostic_graph_aggregator/doc/format/unit/link.md index c23aa92575e54..3649bc49df112 100644 --- a/system/diagnostic_graph_aggregator/doc/format/node/link.md +++ b/system/diagnostic_graph_aggregator/doc/format/unit/link.md @@ -1,10 +1,10 @@ # Link -The `link` object is a node that refers to other nodes. +The `link` object is a unit that refers to another unit. ## Format | Name | Type | Required | Description | | ------ | -------- | -------- | -------------------------------------- | | `type` | `string` | yes | Specify `link` when using this object. | -| `link` | `string` | yes | The path of the node to reference. | +| `link` | `string` | yes | The path of the unit to reference. | diff --git a/system/diagnostic_graph_aggregator/doc/format/node/or.md b/system/diagnostic_graph_aggregator/doc/format/unit/or.md similarity index 66% rename from system/diagnostic_graph_aggregator/doc/format/node/or.md rename to system/diagnostic_graph_aggregator/doc/format/unit/or.md index 74e94ffd628e3..66d0d5fa75125 100644 --- a/system/diagnostic_graph_aggregator/doc/format/node/or.md +++ b/system/diagnostic_graph_aggregator/doc/format/unit/or.md @@ -1,6 +1,6 @@ # Or -The `or` object is a node that is evaluated as the minimum error level of the input nodes. +The `or` object is a unit that is evaluated as the minimum error level of the input units. Note that error level `stale` is treated as `error`. ## Format @@ -8,4 +8,4 @@ Note that error level `stale` is treated as `error`. | Name | Type | Required | Description | | ------ | -------------------------------------- | -------- | ------------------------------------ | | `type` | string | yes | Specify `or` when using this object. | -| `list` | list\[[node](../node.md)] | yes | List of input node objects. | +| `list` | list\[[unit](../unit.md)] | yes | List of input unit objects. | diff --git a/system/diagnostic_graph_aggregator/doc/format/unit/remap.md b/system/diagnostic_graph_aggregator/doc/format/unit/remap.md new file mode 100644 index 0000000000000..35bbf9cb5b408 --- /dev/null +++ b/system/diagnostic_graph_aggregator/doc/format/unit/remap.md @@ -0,0 +1,21 @@ +# Constant + +!!! warning + + This object is under development. It may be removed in the future. + +The remapping object is a unit that converts error levels. + +## Format + +| Name | Type | Required | Description | +| ------ | ------------------------------- | -------- | ---------------------------------------------- | +| `type` | `string` | yes | Specify remapping type when using this object. | +| `item` | [unit](../unit.md) | yes | Input unit object. | + +## Remapping types + +The supported remapping types are as follows. + +- `warn-to-ok` +- `warn-to-error` diff --git a/system/diagnostic_graph_aggregator/doc/message.drawio.svg b/system/diagnostic_graph_aggregator/doc/message.drawio.svg deleted file mode 100644 index aef836dccf235..0000000000000 --- a/system/diagnostic_graph_aggregator/doc/message.drawio.svg +++ /dev/null @@ -1,677 +0,0 @@ - - - - - - - -
-
-
- Top LiDAR -
-
-
-
- Top LiDAR -
-
- - - - -
-
-
- Front LiDAR -
-
-
-
- Front LiDAR -
-
- - - - -
-
-
- obstacle detection -
-
-
-
- obstacle detection -
-
- - - - -
-
-
- pose estimation -
-
-
-
- pose estimation -
-
- - - - -
-
-
- autonomous -
-
-
-
- autonomous -
-
- - - - -
-
-
- remote -
-
-
-
- remote -
-
- - - - -
-
-
- remote command -
-
-
-
- remote command -
-
- - - - -
-
-
- local -
-
-
-
- local -
-
- - - - -
-
-
- joystick command -
-
-
-
- joystick command -
-
- - - - -
-
-
- stop -
-
-
-
- stop -
-
- - - - -
-
-
- Front radar -
-
-
-
- Front radar -
-
- - - - -
-
-
- MRM -
-
-
-
- MRM -
-
- - - - -
-
-
- index -
-
-
-
- index -
-
- - - - -
-
-
- status -
-
-
-
- status -
-
- - - - -
-
-
- 0 -
-
-
-
- 0 -
-
- - - - -
-
-
- 1 -
-
-
-
- 1 -
-
- - - - -
-
-
- 2 -
-
-
-
- 2 -
-
- - - - -
-
-
- 3 -
-
-
-
- 3 -
-
- - - - -
-
-
- 4 -
-
-
-
- 4 -
-
- - - - -
-
-
- 5 -
-
-
-
- 5 -
-
- - - - -
-
-
- 6 -
-
-
-
- 6 -
-
- - - - -
-
-
- 7 -
-
-
-
- 7 -
-
- - - - -
-
-
- 8 -
-
-
-
- 8 -
-
- - - - -
-
-
- 9 -
-
-
-
- 9 -
-
- - - - -
-
-
- 10 -
-
-
-
- 10 -
-
- - - - -
-
-
- 11 -
-
-
-
- 11 -
-
- - - - -
-
-
- links -
-
-
-
- links -
-
- - - - -
-
-
- - -
-
-
-
- - -
-
- - - - -
-
-
- - -
-
-
-
- - -
-
- - - - -
-
-
- 10, 11 -
-
-
-
- 10, 11 -
-
- - - - -
-
-
- 9 -
-
-
-
- 9 -
-
- - - - -
-
-
- 5, 6 -
-
-
-
- 5, 6 -
-
- - - - -
-
-
- 8 -
-
-
-
- 8 -
-
- - - - -
-
-
- - -
-
-
-
- - -
-
- - - - -
-
-
- 7 -
-
-
-
- 7 -
-
- - - - -
-
-
- - -
-
-
-
- - -
-
- - - - -
-
-
- - -
-
-
-
- - -
-
- - - - -
-
-
- - -
-
-
-
- - -
-
- - - - -
-
-
- - -
-
-
-
- - -
-
-
- - - - Text is not SVG - cannot display - - -
diff --git a/system/diagnostic_graph_aggregator/doc/tool/converter.md b/system/diagnostic_graph_aggregator/doc/tool/converter.md deleted file mode 100644 index 2351bc1e01054..0000000000000 --- a/system/diagnostic_graph_aggregator/doc/tool/converter.md +++ /dev/null @@ -1,29 +0,0 @@ -# Converter tool - -This tool converts `/diagnostics_graph` to `/diagnostics_agg` so it can be read by tools such as `rqt_runtime_monitor` and `rqt_robot_monitor`. - -## Usage - -```bash -ros2 launch diagnostic_graph_aggregator converter.launch.xml complement:=false -``` - -The `complement` argument specifies whether to add an intermediate path that does not exist. -This means that if the graph contains paths `/A/B` and `/A/B/C/D/E`, the intermediate paths `/A`, `/A/B/C` and `/A/B/C/D` will be added. -This is useful for tree view in `rqt_robot_monitor`. The completed node has an error level of `STALE`. - -## Examples - -```bash -ros2 launch diagnostic_graph_aggregator example-main.launch.xml complement:=false -ros2 run rqt_runtime_monitor rqt_runtime_monitor --ros-args -r diagnostics:=diagnostics_agg -``` - -![rqt_runtime_monitor](./images/rqt_runtime_monitor.png) - -```bash -ros2 launch diagnostic_graph_aggregator example-main.launch.xml complement:=true -ros2 run rqt_robot_monitor rqt_robot_monitor -``` - -![rqt_robot_monitor](./images/rqt_robot_monitor.png) diff --git a/system/diagnostic_graph_aggregator/doc/tool/dump.md b/system/diagnostic_graph_aggregator/doc/tool/dump.md deleted file mode 100644 index 33f05ff866603..0000000000000 --- a/system/diagnostic_graph_aggregator/doc/tool/dump.md +++ /dev/null @@ -1,36 +0,0 @@ -# Dump tool - -This tool displays `/diagnostics_graph` in table format. - -## Usage - -```bash -ros2 run diagnostic_graph_aggregator dump -``` - -## Examples - -```bash -ros2 launch diagnostic_graph_aggregator example-main.launch.xml -ros2 run diagnostic_graph_aggregator dump -``` - -```txt -| ----- | ----- | -------------------------------- | ----- | -| index | level | name | links | -| ----- | ----- | -------------------------------- | ----- | -| 0 | OK | /sensing/radars/front | | -| 1 | OK | /sensing/lidars/front | | -| 2 | ERROR | /sensing/lidars/top | | -| 3 | OK | /functions/obstacle_detection | 1 0 | -| 4 | ERROR | /functions/pose_estimation | 2 | -| 5 | OK | /external/remote_command | | -| 6 | OK | /external/joystick_command | | -| 7 | ERROR | /autoware/modes/pull_over | 4 3 | -| 8 | OK | /autoware/modes/comfortable_stop | 3 | -| 9 | OK | /autoware/modes/emergency_stop | | -| 10 | OK | /autoware/modes/remote | 5 | -| 11 | OK | /autoware/modes/local | 6 | -| 12 | ERROR | /autoware/modes/autonomous | 4 3 | -| 13 | OK | /autoware/modes/stop | | -``` diff --git a/system/diagnostic_graph_aggregator/doc/tool/images/rqt_robot_monitor.png b/system/diagnostic_graph_aggregator/doc/tool/images/rqt_robot_monitor.png deleted file mode 100644 index e4aa169f02add..0000000000000 Binary files a/system/diagnostic_graph_aggregator/doc/tool/images/rqt_robot_monitor.png and /dev/null differ diff --git a/system/diagnostic_graph_aggregator/doc/tool/tree.md b/system/diagnostic_graph_aggregator/doc/tool/tree.md index 79fa61f527038..12b664ecc48d6 100644 --- a/system/diagnostic_graph_aggregator/doc/tool/tree.md +++ b/system/diagnostic_graph_aggregator/doc/tool/tree.md @@ -11,30 +11,30 @@ ros2 run diagnostic_graph_aggregator tree ## Examples ```bash -ros2 run diagnostic_graph_aggregator tree system/diagnostic_graph_aggregator/example/graph/main.yaml +ros2 run diagnostic_graph_aggregator tree '$(find-pkg-share diagnostic_graph_aggregator)/example/graph/main.yaml' ``` ```txt -===== root nodes ================================= +===== Top-level trees ============================ +- /autoware/modes/autonomous (and) + - /functions/pose_estimation (and) + - /functions/obstacle_detection (or) - /autoware/modes/local (and) - /external/joystick_command (diag) +- /autoware/modes/remote (and) + - /external/remote_command (diag) - /autoware/modes/comfortable_stop (and) - /functions/obstacle_detection (or) - /autoware/modes/pull_over (and) - /functions/pose_estimation (and) - /functions/obstacle_detection (or) -- /autoware/modes/autonomous (and) - - /functions/pose_estimation (and) - - /functions/obstacle_detection (or) -- /autoware/modes/remote (and) - - /external/remote_command (diag) -===== intermediate nodes ========================= +===== Subtrees =================================== +- /functions/pose_estimation (and) + - /sensing/lidars/top (diag) - /functions/obstacle_detection (or) - /sensing/lidars/front (diag) - /sensing/radars/front (diag) -- /functions/pose_estimation (and) - - /sensing/lidars/top (diag) -===== isolated nodes ============================= -- /autoware/modes/stop (const) -- /autoware/modes/emergency_stop (const) +===== Isolated units ============================= +- /autoware/modes/stop (ok) +- /autoware/modes/emergency_stop (ok) ``` diff --git a/system/diagnostic_graph_aggregator/example/dummy-diags.py b/system/diagnostic_graph_aggregator/example/dummy-diags.py index 08f81bcd738ed..210462271a1ea 100755 --- a/system/diagnostic_graph_aggregator/example/dummy-diags.py +++ b/system/diagnostic_graph_aggregator/example/dummy-diags.py @@ -53,9 +53,9 @@ def create_status(name: str): if __name__ == "__main__": diags = [ - "lidar_driver/top: status", - "lidar_driver/front: status", - "radar_driver/front: status", + "lidar_driver_top: status", + "lidar_driver_front: status", + "radar_driver_front: status", "external_command_checker: joystick_command", "external_command_checker: remote_command", ] diff --git a/system/diagnostic_graph_aggregator/example/example-edit.launch.xml b/system/diagnostic_graph_aggregator/example/example-edit.launch.xml index c168b76f19c21..d56f76b1726cf 100644 --- a/system/diagnostic_graph_aggregator/example/example-edit.launch.xml +++ b/system/diagnostic_graph_aggregator/example/example-edit.launch.xml @@ -1,10 +1,6 @@ - - + - - - diff --git a/system/diagnostic_graph_aggregator/example/example-main.launch.xml b/system/diagnostic_graph_aggregator/example/example-main.launch.xml index cdc1bc8afca53..b7019640e993c 100644 --- a/system/diagnostic_graph_aggregator/example/example-main.launch.xml +++ b/system/diagnostic_graph_aggregator/example/example-main.launch.xml @@ -1,10 +1,6 @@ - - - - diff --git a/system/diagnostic_graph_aggregator/example/graph/main.yaml b/system/diagnostic_graph_aggregator/example/graph/main.yaml index 2bea907d9c119..b48c1ebe801ea 100644 --- a/system/diagnostic_graph_aggregator/example/graph/main.yaml +++ b/system/diagnostic_graph_aggregator/example/graph/main.yaml @@ -2,7 +2,7 @@ files: - { path: $(dirname)/module1.yaml } - { path: $(dirname)/module2.yaml } -nodes: +units: - path: /autoware/modes/stop type: ok diff --git a/system/diagnostic_graph_aggregator/example/graph/module1.yaml b/system/diagnostic_graph_aggregator/example/graph/module1.yaml index 07d4951b89446..1e1ae9b994587 100644 --- a/system/diagnostic_graph_aggregator/example/graph/module1.yaml +++ b/system/diagnostic_graph_aggregator/example/graph/module1.yaml @@ -1,4 +1,4 @@ -nodes: +units: - path: /functions/pose_estimation type: and list: @@ -12,12 +12,15 @@ nodes: - path: /sensing/lidars/top type: diag - diag: "lidar_driver/top: status" + node: lidar_driver_top + name: status - path: /sensing/lidars/front type: diag - diag: "lidar_driver/front: status" + node: lidar_driver_front + name: status - path: /sensing/radars/front type: diag - diag: "radar_driver/front: status" + node: radar_driver_front + name: status diff --git a/system/diagnostic_graph_aggregator/example/graph/module2.yaml b/system/diagnostic_graph_aggregator/example/graph/module2.yaml index a03701b661ba9..47e100087c650 100644 --- a/system/diagnostic_graph_aggregator/example/graph/module2.yaml +++ b/system/diagnostic_graph_aggregator/example/graph/module2.yaml @@ -1,8 +1,10 @@ -nodes: +units: - path: /external/joystick_command type: diag - diag: "external_command_checker: joystick_command" + node: external_command_checker + name: joystick_command - path: /external/remote_command type: diag - diag: "external_command_checker: remote_command" + node: external_command_checker + name: remote_command diff --git a/system/diagnostic_graph_aggregator/launch/converter.launch.xml b/system/diagnostic_graph_aggregator/launch/converter.launch.xml deleted file mode 100644 index 9111338bf622a..0000000000000 --- a/system/diagnostic_graph_aggregator/launch/converter.launch.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - diff --git a/system/diagnostic_graph_aggregator/script/dump.py b/system/diagnostic_graph_aggregator/script/dump.py deleted file mode 100755 index 9abcaeb7a080c..0000000000000 --- a/system/diagnostic_graph_aggregator/script/dump.py +++ /dev/null @@ -1,94 +0,0 @@ -#!/usr/bin/env python3 - -# Copyright 2024 The Autoware Contributors -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import argparse - -from diagnostic_msgs.msg import DiagnosticStatus -import rclpy -import rclpy.node -from tier4_system_msgs.msg import DiagnosticGraph - - -def print_table(lines: list, header: list): - widths = [0 for _ in range(len(header))] - lines.insert(0, header) - for line in lines: - widths = map(max, widths, map(len, line)) - widths = list(widths) - lines.insert(0, ["-" * w for w in widths]) - lines.insert(2, ["-" * w for w in widths]) - for line in lines: - line = map(lambda v, w: f"{v:{w}}", line, widths) - line = " | ".join(line) - print(f"| {line} |") - - -def get_level_text(level: int): - if level == DiagnosticStatus.OK: - return "OK" - if level == DiagnosticStatus.WARN: - return "WARN" - if level == DiagnosticStatus.ERROR: - return "ERROR" - if level == DiagnosticStatus.STALE: - return "STALE" - return "-----" - - -class NodeData: - def __init__(self, index, node): - self.index = index - self._node = node - - @property - def level(self): - return get_level_text(self._node.status.level) - - @property - def name(self): - return self._node.status.name - - @property - def links(self): - return " ".join(str(link.index) for link in self._node.links) - - @property - def line(self): - return [str(self.index), self.level, self.name, self.links] - - -class DumpNode(rclpy.node.Node): - def __init__(self, args): - super().__init__("dump_diagnostic_graph") - self.sub = self.create_subscription(DiagnosticGraph, args.topic, self.callback, 1) - - def callback(self, msg): - nodes = [NodeData(index, node) for index, node in enumerate(msg.nodes)] - table = [node.line for node in nodes] - print_table(table, ["index", "level", "name", "links"]) - - -if __name__ == "__main__": - parser = argparse.ArgumentParser() - parser.add_argument("--topic", default="/diagnostics_graph") - args, unparsed = parser.parse_known_args() - - try: - rclpy.init(args=unparsed) - rclpy.spin(DumpNode(args)) - rclpy.shutdown() - except KeyboardInterrupt: - pass diff --git a/system/diagnostic_graph_aggregator/src/common/graph/config.cpp b/system/diagnostic_graph_aggregator/src/common/graph/config.cpp index 39044d1c82bf9..9005084f84503 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/config.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/config.cpp @@ -14,341 +14,297 @@ #include "config.hpp" -#include "error.hpp" +#include "names.hpp" +#include "types.hpp" #include +#include #include -#include +#include #include -#include #include #include #include -#include - -// DEBUG -#include namespace diagnostic_graph_aggregator { -template -void extend(std::vector & u, const std::vector & v) +std::string resolve_substitution(const std::string & substitution, const TreeData & data) { - u.insert(u.end(), v.begin(), v.end()); -} + std::stringstream ss(substitution); + std::string word; + std::vector words; + while (getline(ss, word, ' ')) { + words.push_back(word); + } -template -auto enumerate(const std::vector & v) -{ - std::vector> result; - for (size_t i = 0; i < v.size(); ++i) { - result.push_back(std::make_pair(i, v[i])); + if (words.size() == 2 && words[0] == "find-pkg-share") { + return ament_index_cpp::get_package_share_directory(words[1]); } - return result; + if (words.size() == 1 && words[0] == "dirname") { + return std::filesystem::path(data.path().file()).parent_path(); + } + throw UnknownSubstitution(data.path(), substitution); } -ConfigData::ConfigData(const std::string & path) +std::string resolve_file_path(const std::string & path, const TreeData & data) { - file = path; + static const std::regex pattern(R"(\$\(([^()]*)\))"); + std::smatch m; + std::string result = path; + while (std::regex_search(result, m, pattern)) { + const std::string prefix = m.prefix(); + const std::string suffix = m.suffix(); + result = prefix + resolve_substitution(m.str(1), data) + suffix; + } + return result; } -ConfigData ConfigData::load(YAML::Node yaml) +FileLoader::FileLoader(const PathConfig * path) { - if (!yaml.IsMap()) { - throw error("object is not a dict type", *this); - } - for (const auto & kv : yaml) { - object[kv.first.as()] = kv.second; + if (!std::filesystem::exists(path->resolved)) { + throw FileNotFound(path->data.path(), path->resolved); } - return *this; + + TreeData tree = TreeData::Load(path->resolved); + const auto paths = tree.optional("files").children("files"); + const auto edits = tree.optional("edits").children("edits"); + const auto units = tree.optional("units").children("units"); + for (const auto & data : paths) create_path_config(data); + for (const auto & data : edits) create_edit_config(data); + for (const auto & data : units) create_unit_config(data); } -ConfigData ConfigData::type(const std::string & name) const +PathConfig * FileLoader::create_path_config(const TreeData & data) { - ConfigData data(file); - data.mark = mark.empty() ? name : mark + "-" + name; - return data; + const auto path = paths_.emplace_back(std::make_unique(data)).get(); + path->original = path->data.required("path").text(); + path->resolved = resolve_file_path(path->original, data); + return path; } -ConfigData ConfigData::node(const size_t index) const +EditConfig * FileLoader::create_edit_config(const TreeData & data) { - return type(std::to_string(index)); + const auto edit = edits_.emplace_back(std::make_unique(data)).get(); + edit->type = edit->data.required("type").text(); + return edit; } -std::optional ConfigData::take_yaml(const std::string & name) +UnitConfig * FileLoader::create_unit_config(const TreeData & data) { - if (!object.count(name)) { - return std::nullopt; - } + const auto unit = units_.emplace_back(std::make_unique(data)).get(); + unit->type = unit->data.required("type").text(); + unit->path = unit->data.optional("path").text(); - const auto yaml = object.at(name); - object.erase(name); - return yaml; + const auto item = unit->data.optional("item").child("c"); + if (item.is_valid()) { + unit->item = create_link_config(item, unit); + } + const auto list = unit->data.optional("list").children(); + for (const auto & data : list) { + unit->list.push_back(create_link_config(data, unit)); + } + return unit; } -std::string ConfigData::take_text(const std::string & name) +LinkConfig * FileLoader::create_link_config(const TreeData & data, UnitConfig * unit) { - if (!object.count(name)) { - throw error("required field is not found", name, *this); - } - - const auto yaml = object.at(name); - object.erase(name); - return yaml.as(); + const auto link = links_.emplace_back(std::make_unique()).get(); + link->parent = unit; + link->child = create_unit_config(data); + return link; } -std::string ConfigData::take_text(const std::string & name, const std::string & fail) +void FileLoader::release(FileConfig & config) { - if (!object.count(name)) { - return fail; - } - - const auto yaml = object.at(name); - object.erase(name); - return yaml.as(); + for (auto & path : paths_) config.paths.push_back(std::move(path)); + for (auto & edit : edits_) config.edits.push_back(std::move(edit)); + for (auto & unit : units_) config.units.push_back(std::move(unit)); + for (auto & link : links_) config.links.push_back(std::move(link)); } -std::vector ConfigData::take_list(const std::string & name) +TreeLoader TreeLoader::Load(const std::string & path) { - if (!object.count(name)) { - return std::vector(); - } - - const auto yaml = object.at(name); - object.erase(name); + PathConfig root(TreeData::None()); + root.original = path; + root.resolved = resolve_file_path(path, root.data); + return TreeLoader(&root); +} - if (!yaml.IsSequence()) { - throw error("field is not a list type", name, *this); +TreeLoader::TreeLoader(const PathConfig * root) +{ + std::queue paths; + paths.push(root); + + // TODO(Takagi, Isamu): check include loop. + while (!paths.empty()) { + files_.emplace_back(paths.front()); + paths.pop(); + for (const auto & path : files_.back().paths()) { + paths.push(path.get()); + } } - return std::vector(yaml.begin(), yaml.end()); } -void resolve_link_nodes(RootConfig & root) +auto create_path_mapping(const std::vector> & units) { - std::unordered_map paths; - for (const auto & node : root.nodes) { - if (node->path.empty()) { + std::unordered_map path_to_unit; + for (const auto & unit : units) { + if (unit->path.empty()) { continue; } - if (paths.count(node->path)) { - throw error("object path is not unique", node->path); + if (path_to_unit.count(unit->path)) { + throw PathConflict(unit->path); } - paths[node->path] = node; + path_to_unit[unit->path] = unit.get(); } + return path_to_unit; +} - std::vector nodes; - std::vector links; - for (const auto & node : root.nodes) { - if (node->type == "link") { - links.push_back(node); +void apply_links(FileConfig & config) +{ + // Separate units into link types and others. + std::vector> link_units; + std::vector> node_units; + for (auto & unit : config.units) { + if (unit->type == unit_name::link) { + link_units.push_back(std::move(unit)); } else { - nodes.push_back(node); + node_units.push_back(std::move(unit)); } } - std::unordered_map targets; - for (const auto & node : nodes) { - targets[node] = node; - } - for (const auto & node : links) { - const auto path = node->data.take_text("link"); - if (!paths.count(path)) { - throw error("link path is not found", path, node->data); - } - const auto link = paths.at(path); - if (link->type == "link") { - throw error("link target is link type", path, node->data); + // Create a mapping from path to unit. + const auto path_to_unit = create_path_mapping(node_units); + + // Create a mapping from unit to unit. + std::unordered_map unit_to_unit; + for (const auto & unit : link_units) { + const auto path = unit->data.required("link").text(); + if (path_to_unit.count(path) == 0) { + throw PathNotFound(unit->data.path(), path); } - targets[node] = link; + unit_to_unit[unit.get()] = path_to_unit.at(path); } - for (const auto & node : nodes) { - for (auto & child : node->children) { - child = targets.at(child); + + // Update links. + for (const auto & link : config.links) { + if (unit_to_unit.count(link->child) != 0) { + link->child = unit_to_unit.at(link->child); } } - root.nodes = nodes; + + // Remove link type units from the graph. + config.units = std::move(node_units); } -void resolve_remove_edits(RootConfig & root) +void apply_edits(FileConfig & config) { - std::unordered_map paths; - for (const auto & node : root.nodes) { - paths[node->path] = node; - } - - std::unordered_set removes; - for (const auto & edit : root.edits) { - if (edit->type == "remove") { - if (!paths.count(edit->path)) { - throw error("remove path is not found", edit->path, edit->data); + // Create a mapping from path to unit. + const auto path_to_unit = create_path_mapping(config.units); + + // List units to remove and links from/to them. + std::unordered_set remove_units; + std::unordered_set remove_links; + for (const auto & edit : config.edits) { + if (edit->type == edit_name::remove) { + const auto path = edit->data.required("path").text(); + if (path_to_unit.count(path) == 0) { + throw PathNotFound(edit->data.path(), path); } - removes.insert(paths.at(edit->path)); + remove_units.insert(path_to_unit.at(path)); } } - - const auto filter = [removes](const std::vector & nodes) { - std::vector result; - for (const auto & node : nodes) { - if (!removes.count(node)) { - result.push_back(node); - } + for (const auto & link : config.links) { + if (remove_units.count(link->parent) || remove_units.count(link->child)) { + remove_links.insert(link.get()); } - return result; - }; - for (const auto & node : root.nodes) { - node->children = filter(node->children); - } - root.nodes = filter(root.nodes); -} - -std::string complement_node_type(ConfigData & data) -{ - if (data.object.count("diag")) { - return "diag"; } - return data.take_text("type"); -} -std::string resolve_substitution(const std::string & substitution, const ConfigData & data) -{ - std::stringstream ss(substitution); - std::string word; - std::vector words; - while (getline(ss, word, ' ')) { - words.push_back(word); + // Filter references to the removed links. + for (const auto & unit : config.units) { + if (remove_links.count(unit->item) != 0) { + unit->item = nullptr; + } + std::vector filtered_list; + for (const auto & link : unit->list) { + if (remove_links.count(link) == 0) { + filtered_list.push_back(link); + } + unit->list = filtered_list; + } } - if (words.size() == 2 && words[0] == "find-pkg-share") { - return ament_index_cpp::get_package_share_directory(words[1]); - } - if (words.size() == 1 && words[0] == "dirname") { - return std::filesystem::path(data.file).parent_path(); + // Remove units and links. + std::vector> filtered_units; + std::vector> filtered_links; + for (auto & unit : config.units) { + if (remove_units.count(unit.get()) == 0) { + filtered_units.push_back(std::move(unit)); + } } - throw error("unknown substitution", substitution, data); -} - -std::string resolve_file_path(const std::string & path, const ConfigData & data) -{ - static const std::regex pattern(R"(\$\(([^()]*)\))"); - std::smatch m; - std::string result = path; - while (std::regex_search(result, m, pattern)) { - const std::string prefix = m.prefix(); - const std::string suffix = m.suffix(); - result = prefix + resolve_substitution(m.str(1), data) + suffix; + for (auto & link : config.links) { + if (remove_links.count(link.get()) == 0) { + filtered_links.push_back(std::move(link)); + } } - return result; + config.units = std::move(filtered_units); + config.links = std::move(filtered_links); } -PathConfig::SharedPtr parse_path_config(const ConfigData & data) +void topological_sort(FileConfig & config) { - const auto path = std::make_shared(data); - path->original = path->data.take_text("path"); - path->resolved = resolve_file_path(path->original, path->data); - return path; -} - -UnitConfig::SharedPtr parse_node_config(const ConfigData & data) -{ - const auto node = std::make_shared(data); - node->path = node->data.take_text("path", ""); - node->type = node->data.take_text("type", ""); - - if (node->type.empty()) { - node->type = complement_node_type(node->data); + std::unordered_map degrees; + std::deque units; + std::deque result; + std::deque buffer; + + // Create a list of raw pointer units. + for (const auto & unit : config.units) units.push_back(unit.get()); + + // Count degrees of each unit. + for (const auto & unit : units) { + if (const auto & link = unit->item) ++degrees[link->child]; + for (const auto & link : unit->list) ++degrees[link->child]; } - for (const auto & [index, yaml] : enumerate(node->data.take_list("list"))) { - const auto child = data.node(index).load(yaml); - node->children.push_back(parse_node_config(child)); + // Find initial units that are zero degrees. + for (const auto & unit : units) { + if (degrees[unit] == 0) buffer.push_back(unit); } - return node; -} - -EditConfig::SharedPtr parse_edit_config(const ConfigData & data) -{ - const auto edit = std::make_shared(data); - edit->path = edit->data.take_text("path", ""); - edit->type = edit->data.take_text("type", ""); - return edit; -} -FileConfig::SharedPtr parse_file_config(const ConfigData & data) -{ - const auto file = std::make_shared(data); - const auto path_data = data.type("file"); - const auto node_data = data.type("node"); - const auto edit_data = data.type("edit"); - const auto paths = file->data.take_list("files"); - const auto nodes = file->data.take_list("nodes"); - const auto edits = file->data.take_list("edits"); - - for (const auto & [index, yaml] : enumerate(paths)) { - const auto path = path_data.node(index).load(yaml); - file->paths.push_back(parse_path_config(path)); - } - for (const auto & [index, yaml] : enumerate(nodes)) { - const auto node = node_data.node(index).load(yaml); - file->nodes.push_back(parse_node_config(node)); - } - for (const auto & [index, yaml] : enumerate(edits)) { - const auto edit = edit_data.node(index).load(yaml); - file->edits.push_back(parse_edit_config(edit)); + // Sort by topological order. + while (!buffer.empty()) { + const auto unit = buffer.front(); + buffer.pop_front(); + if (const auto & link = unit->item) { + if (--degrees[link->child] == 0) { + buffer.push_back(link->child); + } + } + for (const auto & link : unit->list) { + if (--degrees[link->child] == 0) { + buffer.push_back(link->child); + } + } + result.push_back(unit); } - return file; -} -FileConfig::SharedPtr load_file_config(PathConfig & config) -{ - const auto path = std::filesystem::path(config.resolved); - if (!std::filesystem::exists(path)) { - throw error("file is not found", path, config.data); + // Detect circulation because the result does not include the units on the loop. + if (result.size() != units.size()) { + throw GraphStructure("detect graph circulation"); } - const auto file = ConfigData(path).load(YAML::LoadFile(path)); - return parse_file_config(file); } -RootConfig load_root_config(const PathConfig::SharedPtr root) +FileConfig TreeLoader::construct() { - std::vector paths; - paths.push_back(root); - - std::vector files; - for (size_t i = 0; i < paths.size(); ++i) { - const auto path = paths[i]; - const auto file = load_file_config(*path); - files.push_back(file); - extend(paths, file->paths); - } - - std::vector nodes; - std::vector edits; - for (const auto & file : files) { - extend(nodes, file->nodes); - extend(edits, file->edits); - } - for (size_t i = 0; i < nodes.size(); ++i) { - const auto node = nodes[i]; - extend(nodes, node->children); - } - - RootConfig config; - config.files = files; - config.nodes = nodes; - config.edits = edits; - resolve_link_nodes(config); - resolve_remove_edits(config); + FileConfig config; + for (auto & file : files_) file.release(config); + apply_links(config); + apply_edits(config); + topological_sort(config); // Check graph structure. return config; } -RootConfig load_root_config(const std::string & path) -{ - const auto root = std::make_shared(ConfigData("root-file")); - root->original = path; - root->resolved = path; - return load_root_config(root); -} - } // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/config.hpp b/system/diagnostic_graph_aggregator/src/common/graph/config.hpp index 40f16235ed5d6..a22daf907a27e 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/config.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/config.hpp @@ -15,114 +15,87 @@ #ifndef COMMON__GRAPH__CONFIG_HPP_ #define COMMON__GRAPH__CONFIG_HPP_ -#include +#include "data.hpp" +#include "types.hpp" #include -#include #include -#include #include namespace diagnostic_graph_aggregator { -struct ConfigData +struct PathConfig { - explicit ConfigData(const std::string & file); - ConfigData load(YAML::Node yaml); - ConfigData type(const std::string & name) const; - ConfigData node(const size_t index) const; - - template - T take(const std::string & name, const T & fail) - { - const auto yaml = take_yaml(name); - return yaml ? yaml.value().as() : fail; - } - - std::optional take_yaml(const std::string & name); - std::string take_text(const std::string & name); - std::string take_text(const std::string & name, const std::string & fail); - std::vector take_list(const std::string & name); - - std::string file; - std::string mark; - std::unordered_map object; -}; - -struct BaseConfig -{ - explicit BaseConfig(const ConfigData & data) : data(data) {} - ConfigData data; -}; - -struct PathConfig : public BaseConfig -{ - using SharedPtr = std::shared_ptr; - using BaseConfig::BaseConfig; + explicit PathConfig(const TreeData & data) : data(data) {} + TreeData data; std::string original; std::string resolved; }; -struct UnitConfig : public BaseConfig +struct EditConfig { - using SharedPtr = std::shared_ptr; - using BaseConfig::BaseConfig; + explicit EditConfig(const TreeData & data) : data(data) {} + TreeData data; std::string type; - std::string path; - std::vector children; }; -struct EditConfig : public BaseConfig +struct LinkConfig { - using SharedPtr = std::shared_ptr; - using BaseConfig::BaseConfig; - std::string type; - std::string path; + UnitConfig * parent = nullptr; + UnitConfig * child = nullptr; }; -struct FileConfig : public BaseConfig +struct UnitConfig { - using SharedPtr = std::shared_ptr; - using BaseConfig::BaseConfig; - std::vector paths; - std::vector nodes; - std::vector edits; + explicit UnitConfig(const TreeData & data) : data(data) {} + TreeData data; + std::string type; + std::string path; + LinkConfig * item = nullptr; + std::vector list; + size_t index; }; -struct RootConfig +struct FileConfig { - std::vector files; - std::vector nodes; - std::vector edits; + // Note: keep order correspondence between links and unit children for viewer. + std::vector> paths; + std::vector> edits; + std::vector> units; + std::vector> links; }; -template -T error(const std::string & text, const ConfigData & data) -{ - const auto hint = data.mark.empty() ? data.file : data.mark + ":" + data.file; - return T(text + " (" + hint + ")"); -} - -template -T error(const std::string & text) +class FileLoader { - return T(text); -} - -template -T error(const std::string & text, const std::string & value, const ConfigData & data) -{ - return error(text + ": " + value, data); -} +public: + explicit FileLoader(const PathConfig * path); + const auto & paths() const { return paths_; } + void release(FileConfig & config); + +private: + PathConfig * create_path_config(const TreeData & data); + EditConfig * create_edit_config(const TreeData & data); + UnitConfig * create_unit_config(const TreeData & data); + LinkConfig * create_link_config(const TreeData & data, UnitConfig * unit); + + // Note: keep order correspondence between links and unit children for viewer. + std::vector> paths_; + std::vector> edits_; + std::vector> units_; + std::vector> links_; +}; -template -T error(const std::string & text, const std::string & value) +class TreeLoader { - return error(text + ": " + value); -} +public: + static TreeLoader Load(const std::string & path); + explicit TreeLoader(const PathConfig * root); + FileConfig construct(); -RootConfig load_root_config(const std::string & path); +private: + std::vector files_; +}; } // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/data.cpp b/system/diagnostic_graph_aggregator/src/common/graph/data.cpp new file mode 100644 index 0000000000000..ff186098c32e3 --- /dev/null +++ b/system/diagnostic_graph_aggregator/src/common/graph/data.cpp @@ -0,0 +1,97 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "data.hpp" + +namespace diagnostic_graph_aggregator +{ + +TreeData TreeData::Load(const std::string & path) +{ + return TreeData(YAML::LoadFile(path), TreePath(path)); +} + +TreeData TreeData::None() +{ + return TreeData(YAML::Node(), TreePath("")); +} + +TreeData::TreeData(const YAML::Node & yaml, const TreePath & path) : path_(path) +{ + yaml_ = yaml; +} + +TreeData::Item TreeData::required(const std::string & name) +{ + // TODO(Takagi, Isamu): check map type. + const auto path = path_.field(name); + if (!yaml_[name]) { + throw FieldNotFound(path); + } + const auto data = yaml_[name]; + yaml_.remove(name); + return TreeData(data, path); +} + +TreeData::Item TreeData::optional(const std::string & name) +{ + // TODO(Takagi, Isamu): check map type. + const auto path = path_.field(name); + if (!yaml_[name]) { + return TreeData(YAML::Node(YAML::NodeType::Undefined), path); + } + const auto data = yaml_[name]; + yaml_.remove(name); + return TreeData(data, path); +} + +bool TreeData::is_valid() const +{ + return yaml_.Type() != YAML::NodeType::Undefined; +} + +TreeData::Item TreeData::child(const std::string & path) +{ + return TreeData(yaml_, path_.child(path)); +} + +TreeData::List TreeData::children(const std::string & path) +{ + if (yaml_.Type() == YAML::NodeType::Undefined) { + return {}; + } + if (yaml_.Type() != YAML::NodeType::Sequence) { + throw InvalidType(path_); + } + + TreeData::List result; + for (size_t i = 0; i < yaml_.size(); ++i) { + result.emplace_back(yaml_[i], path_.child(path, i)); + } + return result; +} + +std::string TreeData::text(const std::string & fail) +{ + // TODO(Takagi, Isamu): check conversion failure + return yaml_.as(fail); +} + +double TreeData::real(double fail) +{ + // TODO(Takagi, Isamu): check conversion failure + return yaml_.as(fail); +} + +} // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/data.hpp b/system/diagnostic_graph_aggregator/src/common/graph/data.hpp new file mode 100644 index 0000000000000..437e3793df398 --- /dev/null +++ b/system/diagnostic_graph_aggregator/src/common/graph/data.hpp @@ -0,0 +1,56 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef COMMON__GRAPH__DATA_HPP_ +#define COMMON__GRAPH__DATA_HPP_ + +#include "error.hpp" + +#include + +#include +#include +#include + +namespace diagnostic_graph_aggregator +{ + +class TreeData +{ +public: + using Item = TreeData; + using List = std::vector; + + static TreeData Load(const std::string & path); + static TreeData None(); + TreeData(const YAML::Node & yaml, const TreePath & path); + + const auto & path() const { return path_; } + Item required(const std::string & name); + Item optional(const std::string & name); + bool is_valid() const; + + Item child(const std::string & path); + List children(const std::string & path = ""); + std::string text(const std::string & fail = ""); + double real(double fail); + +private: + YAML::Node yaml_; + TreePath path_; +}; + +} // namespace diagnostic_graph_aggregator + +#endif // COMMON__GRAPH__DATA_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/common/graph/debug.cpp b/system/diagnostic_graph_aggregator/src/common/graph/debug.cpp deleted file mode 100644 index 8f2b741edd805..0000000000000 --- a/system/diagnostic_graph_aggregator/src/common/graph/debug.cpp +++ /dev/null @@ -1,75 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "debug.hpp" - -#include "graph.hpp" -#include "types.hpp" -#include "units.hpp" - -#include -#include -#include -#include - -namespace diagnostic_graph_aggregator -{ - -std::string get_level_text(DiagnosticLevel level) -{ - switch (level) { - case DiagnosticStatus::OK: - return "OK"; - case DiagnosticStatus::WARN: - return "WARN"; - case DiagnosticStatus::ERROR: - return "ERROR"; - case DiagnosticStatus::STALE: - return "STALE"; - } - return "UNKNOWN"; -} - -void Graph::debug() -{ - std::vector lines; - for (const auto & node : nodes_) { - const auto level_name = get_level_text(node->level()); - const auto index_name = std::to_string(node->index()); - lines.push_back({index_name, level_name, node->path(), node->type()}); - } - for (const auto & [name, level] : unknowns_) { - const auto level_name = get_level_text(level); - lines.push_back({"*", level_name, name, "unknown"}); - } - - std::array widths = {}; - for (const auto & line : lines) { - for (size_t i = 0; i < diag_debug_size; ++i) { - widths[i] = std::max(widths[i], line[i].length()); - } - } - - const size_t total_width = std::accumulate(widths.begin(), widths.end(), 0); - std::cout << std::string(total_width + 3 * diag_debug_size + 1, '=') << std::endl; - - for (const auto & line : lines) { - for (size_t i = 0; i < diag_debug_size; ++i) { - std::cout << "| " << std::left << std::setw(widths[i]) << line[i] << " "; - } - std::cout << "|" << std::endl; - } -} - -} // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/debug.hpp b/system/diagnostic_graph_aggregator/src/common/graph/debug.hpp deleted file mode 100644 index 69a0eeb2c8023..0000000000000 --- a/system/diagnostic_graph_aggregator/src/common/graph/debug.hpp +++ /dev/null @@ -1,29 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef COMMON__GRAPH__DEBUG_HPP_ -#define COMMON__GRAPH__DEBUG_HPP_ - -#include -#include - -namespace diagnostic_graph_aggregator -{ - -constexpr size_t diag_debug_size = 4; -using DiagDebugData = std::array; - -} // namespace diagnostic_graph_aggregator - -#endif // COMMON__GRAPH__DEBUG_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/common/graph/error.cpp b/system/diagnostic_graph_aggregator/src/common/graph/error.cpp new file mode 100644 index 0000000000000..e78a444c5ab7f --- /dev/null +++ b/system/diagnostic_graph_aggregator/src/common/graph/error.cpp @@ -0,0 +1,58 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "error.hpp" + +namespace diagnostic_graph_aggregator +{ + +TreePath::TreePath(const std::string & file) +{ + file_ = file; +} + +TreePath TreePath::field(const std::string & name) +{ + TreePath result(file_); + result.node_ = node_; + result.name_ = name; + return result; +} + +TreePath TreePath::child(const std::string & path) +{ + const auto sep = node_.empty() ? "" : "-"; + TreePath result(file_); + result.node_ = node_ + sep + path; + return result; +} + +TreePath TreePath::child(const std::string & path, const size_t index) +{ + const auto sep = path.empty() ? "" : "-"; + return child(path + sep + std::to_string(index)); +} + +TreePath TreePath::child(const size_t index) +{ + return child(std::to_string(index)); +} + +std::string TreePath::text() const +{ + const auto sep = node_.empty() ? "" : ":"; + return " (" + file_ + sep + node_ + ")"; +} + +} // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/error.hpp b/system/diagnostic_graph_aggregator/src/common/graph/error.hpp index dadfab450c783..d923e12caf783 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/error.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/error.hpp @@ -16,51 +16,113 @@ #define COMMON__GRAPH__ERROR_HPP_ #include +#include namespace diagnostic_graph_aggregator { +struct TreePath +{ + explicit TreePath(const std::string & file); + TreePath field(const std::string & name); + TreePath child(const std::string & path); + TreePath child(const std::string & path, const size_t index); + TreePath child(const size_t index); + std::string text() const; + std::string file() const { return file_; } + std::string node() const { return node_; } + std::string name() const { return name_; } + +private: + std::string file_; + std::string node_; + std::string name_; +}; + struct Exception : public std::runtime_error { using runtime_error::runtime_error; }; -class FileNotFound : public Exception +struct FileNotFound : public Exception { - using Exception::Exception; + explicit FileNotFound(const TreePath & path, const std::string & file) + : Exception(format(path, file)) + { + } + static std::string format(const TreePath & path, const std::string & file) + { + return "file is not found: " + file + path.text(); + } }; -class UnknownType : public Exception +struct FieldNotFound : public Exception { - using Exception::Exception; + explicit FieldNotFound(const TreePath & path) : Exception(format(path)) {} + static std::string format(const TreePath & path) + { + return "required field is not found: " + path.name() + path.text(); + } }; -class InvalidType : public Exception +struct InvalidType : public Exception { - using Exception::Exception; + explicit InvalidType(const TreePath & path) : Exception(format(path)) {} + static std::string format(const TreePath & path) + { + return "field is not a list type: " + path.name() + path.text(); + } }; -class InvalidValue : public Exception +struct ModeNotFound : public Exception { - using Exception::Exception; + explicit ModeNotFound(const std::string & path) : Exception(format(path)) {} + static std::string format(const std::string & path) { return "mode path is not found: " + path; } }; -class FieldNotFound : public Exception +struct PathConflict : public Exception { - using Exception::Exception; + explicit PathConflict(const std::string & path) : Exception(format(path)) {} + static std::string format(const std::string & path) { return "node path is not unique: " + path; } }; -class PathConflict : public Exception +struct PathNotFound : public Exception { - using Exception::Exception; + explicit PathNotFound(const TreePath & path, const std::string & link) + : Exception(format(path, link)) + { + } + static std::string format(const TreePath & path, const std::string & link) + { + return "path is not found: " + link + path.text(); + } }; -class PathNotFound : public Exception +struct UnknownSubstitution : public Exception { - using Exception::Exception; + explicit UnknownSubstitution(const TreePath & path, const std::string & substitution) + : Exception(format(path, substitution)) + { + } + static std::string format(const TreePath & path, const std::string & substitution) + { + return "unknown substitution: " + substitution + path.text(); + } +}; + +struct UnknownUnitType : public Exception +{ + explicit UnknownUnitType(const TreePath & path, const std::string & type) + : Exception(format(path, type)) + { + } + static std::string format(const TreePath & path, const std::string & type) + { + return "unknown unit type: " + type + path.text(); + } }; -class GraphStructure : public Exception +struct GraphStructure : public Exception { using Exception::Exception; }; diff --git a/system/diagnostic_graph_aggregator/src/common/graph/graph.cpp b/system/diagnostic_graph_aggregator/src/common/graph/graph.cpp index 5d7c11879a9cc..0a7d78a5ce982 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/graph.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/graph.cpp @@ -16,211 +16,64 @@ #include "config.hpp" #include "error.hpp" +#include "loader.hpp" #include "units.hpp" -#include -#include -#include #include -#include -#include - -// DEBUG -#include namespace diagnostic_graph_aggregator { -BaseUnit::UniquePtrList topological_sort(BaseUnit::UniquePtrList && input) -{ - std::unordered_map degrees; - std::deque nodes; - std::deque result; - std::deque buffer; - - // Create a list of raw pointer nodes. - for (const auto & node : input) { - nodes.push_back(node.get()); - } - - // Count degrees of each node. - for (const auto & node : nodes) { - for (const auto & child : node->children()) { - ++degrees[child]; - } - } - - // Find initial nodes that are zero degrees. - for (const auto & node : nodes) { - if (degrees[node] == 0) { - buffer.push_back(node); - } - } - - // Sort by topological order. - while (!buffer.empty()) { - const auto node = buffer.front(); - buffer.pop_front(); - for (const auto & child : node->children()) { - if (--degrees[child] == 0) { - buffer.push_back(child); - } - } - result.push_back(node); - } - - // Detect circulation because the result does not include the nodes on the loop. - if (result.size() != nodes.size()) { - throw error("detect graph circulation"); - } - - // Reverse the result to process from leaf node. - result = std::deque(result.rbegin(), result.rend()); - - // Replace node vector. - std::unordered_map indices; - for (size_t i = 0; i < result.size(); ++i) { - indices[result[i]] = i; - } - std::vector> sorted(input.size()); - for (auto & node : input) { - sorted[indices[node.get()]] = std::move(node); - } - return sorted; -} - -BaseUnit::UniquePtr make_node(const UnitConfig::SharedPtr & config) -{ - if (config->type == "diag") { - return std::make_unique(config->path); - } - if (config->type == "and") { - return std::make_unique(config->path, false); - } - if (config->type == "short-circuit-and") { - return std::make_unique(config->path, true); - } - if (config->type == "or") { - return std::make_unique(config->path); - } - if (config->type == "warn-to-ok") { - return std::make_unique(config->path, DiagnosticStatus::OK); - } - if (config->type == "warn-to-error") { - return std::make_unique(config->path, DiagnosticStatus::ERROR); - } - if (config->type == "ok") { - return std::make_unique(config->path, DiagnosticStatus::OK); - } - if (config->type == "warn") { - return std::make_unique(config->path, DiagnosticStatus::WARN); - } - if (config->type == "error") { - return std::make_unique(config->path, DiagnosticStatus::ERROR); - } - if (config->type == "stale") { - return std::make_unique(config->path, DiagnosticStatus::STALE); - } - throw error("unknown node type", config->type, config->data); -} - -Graph::Graph() +void Graph::create(const std::string & file, const std::string & id) { - // for unique_ptr + GraphLoader graph(file); + nodes_ = graph.release_nodes(); + diags_ = graph.release_diags(); + links_ = graph.release_links(); + for (const auto & diag : diags_) names_[diag->name()] = diag.get(); + for (const auto & node : nodes_) units_.push_back(node.get()); + for (const auto & diag : diags_) units_.push_back(diag.get()); + + id_ = id; } -Graph::~Graph() +void Graph::update(const rclcpp::Time & stamp) { - // for unique_ptr + for (const auto & diag : diags_) diag->on_time(stamp); } -void Graph::init(const std::string & file) +bool Graph::update(const rclcpp::Time & stamp, const DiagnosticStatus & status) { - BaseUnit::UniquePtrList nodes; - BaseUnit::NodeDict dict; - - for (const auto & config : load_root_config(file).nodes) { - const auto node = nodes.emplace_back(make_node(config)).get(); - dict.configs[config] = node; - dict.paths[config->path] = node; - } - dict.paths.erase(""); - - for (const auto & [config, node] : dict.configs) { - node->init(config, dict); - } - - // Sort units in topological order for update dependencies. - nodes = topological_sort(std::move(nodes)); - - // List diag nodes that have diag name. - for (const auto & node : nodes) { - const auto diag = dynamic_cast(node.get()); - if (diag) { - diags_[diag->name()] = diag; - } - } - - // List unit nodes that have path name. - for (const auto & node : nodes) { - if (!node->path().empty()) { - units_.push_back(node.get()); - } - } - - // Set unit index. - for (size_t index = 0; index < units_.size(); ++index) { - units_[index]->set_index(index); - } - - nodes_ = std::move(nodes); + const auto iter = names_.find(status.name); + if (iter == names_.end()) return false; + iter->second->on_diag(stamp, status); + return true; } -void Graph::callback(const rclcpp::Time & stamp, const DiagnosticArray & array) +DiagGraphStruct Graph::create_struct(const rclcpp::Time & stamp) const { - for (const auto & status : array.status) { - const auto iter = diags_.find(status.name); - if (iter != diags_.end()) { - iter->second->callback(stamp, status); - } else { - unknowns_[status.name] = status.level; - } - } + DiagGraphStruct msg; + msg.stamp = stamp; + msg.id = id_; + for (const auto & node : nodes_) msg.nodes.push_back(node->create_struct()); + for (const auto & diag : diags_) msg.diags.push_back(diag->create_struct()); + for (const auto & link : links_) msg.links.push_back(link->create_struct()); + return msg; } -DiagnosticGraph Graph::report(const rclcpp::Time & stamp) +DiagGraphStatus Graph::create_status(const rclcpp::Time & stamp) const { - for (const auto & node : nodes_) { - node->update(stamp); - } - - DiagnosticGraph message; - message.stamp = stamp; - message.nodes.reserve(units_.size()); - for (const auto & node : units_) { - const auto report = node->report(); - DiagnosticNode temp; - temp.status.name = node->path(); - temp.status.level = report.level; - for (const auto & [ref, used] : report.links) { - DiagnosticLink link; - link.index = ref->index(); - link.used = used; - temp.links.push_back(link); - } - message.nodes.push_back(temp); - } - return message; + DiagGraphStatus msg; + msg.stamp = stamp; + msg.id = id_; + for (const auto & node : nodes_) msg.nodes.push_back(node->create_status()); + for (const auto & diag : diags_) msg.diags.push_back(diag->create_status()); + for (const auto & link : links_) msg.links.push_back(link->create_status()); + return msg; } -std::vector Graph::nodes() const -{ - std::vector result; - result.reserve(nodes_.size()); - for (const auto & node : nodes_) { - result.push_back(node.get()); - } - return result; -} +// For unique_ptr members. +Graph::Graph() = default; +Graph::~Graph() = default; } // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/graph.hpp b/system/diagnostic_graph_aggregator/src/common/graph/graph.hpp index 8c29a303814b8..ed7bac0e96ce3 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/graph.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/graph.hpp @@ -22,29 +22,34 @@ #include #include #include -#include #include namespace diagnostic_graph_aggregator { -class Graph final +class Graph { public: - Graph(); - ~Graph(); - - void init(const std::string & file); - void callback(const rclcpp::Time & stamp, const DiagnosticArray & array); - void debug(); - DiagnosticGraph report(const rclcpp::Time & stamp); - std::vector nodes() const; + void create(const std::string & file, const std::string & id = ""); + void update(const rclcpp::Time & stamp); + bool update(const rclcpp::Time & stamp, const DiagnosticStatus & status); + const auto & nodes() const { return nodes_; } + const auto & diags() const { return diags_; } + const auto & units() const { return units_; } + DiagGraphStruct create_struct(const rclcpp::Time & stamp) const; + DiagGraphStatus create_status(const rclcpp::Time & stamp) const; + + Graph(); // For unique_ptr members. + ~Graph(); // For unique_ptr members. private: - std::vector> nodes_; + // Note: keep order correspondence between links and unit children for viewer. + std::vector> nodes_; + std::vector> diags_; + std::vector> links_; std::vector units_; - std::unordered_map diags_; - std::unordered_map unknowns_; + std::unordered_map names_; + std::string id_; }; } // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/loader.cpp b/system/diagnostic_graph_aggregator/src/common/graph/loader.cpp new file mode 100644 index 0000000000000..74636adab7415 --- /dev/null +++ b/system/diagnostic_graph_aggregator/src/common/graph/loader.cpp @@ -0,0 +1,189 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "loader.hpp" + +#include "config.hpp" +#include "error.hpp" +#include "names.hpp" +#include "types.hpp" +#include "units.hpp" + +#include + +namespace diagnostic_graph_aggregator +{ + +struct UnitLoader::GraphLinks +{ + std::unordered_map config_links; + std::unordered_map> parent_links; +}; + +size_t UnitLoader::index() const +{ + return config_->index; +} + +const std::string & UnitLoader::path() const +{ + return config_->path; +} + +const std::string & UnitLoader::type() const +{ + return config_->type; +} + +TreeData & UnitLoader::data() const +{ + return config_->data; +} + +UnitLink * UnitLoader::child() const +{ + return links_.config_links.at(config_->item); +} + +std::vector UnitLoader::children() const +{ + std::vector result; + for (const auto & config : config_->list) { + result.push_back(links_.config_links.at(config)); + } + return result; +} + +std::vector UnitLoader::parents() const +{ + return links_.parent_links.at(config_); +} + +GraphLoader::GraphLoader(const std::string & file) +{ + TreeLoader tree = TreeLoader::Load(file); + FileConfig root = tree.construct(); + + // Init array index to be able get it from unit itself. + std::vector diags; + std::vector nodes; + for (const auto & config : root.units) { + (config->type == unit_name::diag ? diags : nodes).push_back(config.get()); + } + for (size_t i = 0; i < diags.size(); ++i) diags[i]->index = i; + for (size_t i = 0; i < nodes.size(); ++i) nodes[i]->index = i; + + // Create link objects. + UnitLoader::GraphLinks graph_links; + for (const auto & config : root.units) { + graph_links.parent_links[config.get()] = {}; + } + for (const auto & config : root.links) { + const auto link = links_.emplace_back(create_link()).get(); + graph_links.config_links[config.get()] = link; + graph_links.parent_links[config->child].push_back(link); + } + + // Create node objects. + std::unordered_map config_units; + for (const auto & config : diags) { + const auto unit = UnitLoader(config, graph_links); + const auto diag = diags_.emplace_back(create_diag(unit)).get(); + config_units[config] = diag; + } + for (const auto & config : nodes) { + const auto unit = UnitLoader(config, graph_links); + const auto node = nodes_.emplace_back(create_node(unit)).get(); + config_units[config] = node; + } + + // Connect links and nodes; + for (const auto & [config, link] : graph_links.config_links) { + const auto parent = config_units.at(config->parent); + const auto child = config_units.at(config->child); + link->initialize_object(parent, child); + } + + // Init struct. + for (auto & node : nodes_) node->initialize_struct(); + for (auto & diag : diags_) diag->initialize_struct(); + for (auto & link : links_) link->initialize_struct(); + + // Init status that needs struct. + for (auto & node : nodes_) node->initialize_status(); + for (auto & diag : diags_) diag->initialize_status(); + for (auto & link : links_) link->initialize_status(); +} + +std::vector> GraphLoader::release_links() +{ + return std::move(links_); +} + +std::vector> GraphLoader::release_nodes() +{ + return std::move(nodes_); +} + +std::vector> GraphLoader::release_diags() +{ + return std::move(diags_); +} + +std::unique_ptr GraphLoader::create_link() +{ + return std::make_unique(); +} + +std::unique_ptr GraphLoader::create_diag(const UnitLoader & unit) +{ + if (unit.type() == unit_name::diag) { + return std::make_unique(unit); + } + throw UnknownUnitType(unit.data().path(), unit.type()); +} + +std::unique_ptr GraphLoader::create_node(const UnitLoader & unit) +{ + if (unit.type() == unit_name::max) { + return std::make_unique(unit); + } + if (unit.type() == unit_name::short_circuit_max) { + return std::make_unique(unit); + } + if (unit.type() == unit_name::min) { + return std::make_unique(unit); + } + if (unit.type() == unit_name::warn_to_ok) { + return std::make_unique(unit); + } + if (unit.type() == unit_name::warn_to_error) { + return std::make_unique(unit); + } + if (unit.type() == unit_name::ok) { + return std::make_unique(unit); + } + if (unit.type() == unit_name::warn) { + return std::make_unique(unit); + } + if (unit.type() == unit_name::error) { + return std::make_unique(unit); + } + if (unit.type() == unit_name::stale) { + return std::make_unique(unit); + } + throw UnknownUnitType(unit.data().path(), unit.type()); +} + +} // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/loader.hpp b/system/diagnostic_graph_aggregator/src/common/graph/loader.hpp new file mode 100644 index 0000000000000..226b3ab279b22 --- /dev/null +++ b/system/diagnostic_graph_aggregator/src/common/graph/loader.hpp @@ -0,0 +1,67 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef COMMON__GRAPH__LOADER_HPP_ +#define COMMON__GRAPH__LOADER_HPP_ + +#include "types.hpp" + +#include +#include +#include +#include + +namespace diagnostic_graph_aggregator +{ + +class UnitLoader +{ +public: + struct GraphLinks; + UnitLoader(UnitConfig * config, GraphLinks & links) : config_(config), links_(links) {} + const std::string & path() const; + const std::string & type() const; + size_t index() const; + TreeData & data() const; + UnitLink * child() const; + std::vector children() const; + std::vector parents() const; + +private: + UnitConfig * config_; + GraphLinks & links_; +}; + +class GraphLoader +{ +public: + explicit GraphLoader(const std::string & file); + std::vector> release_nodes(); + std::vector> release_diags(); + std::vector> release_links(); + +private: + std::unique_ptr create_link(); + std::unique_ptr create_diag(const UnitLoader & unit); + std::unique_ptr create_node(const UnitLoader & unit); + + // Note: keep order correspondence between links and unit children for viewer. + std::vector> nodes_; + std::vector> diags_; + std::vector> links_; +}; + +} // namespace diagnostic_graph_aggregator + +#endif // COMMON__GRAPH__LOADER_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/common/graph/names.hpp b/system/diagnostic_graph_aggregator/src/common/graph/names.hpp new file mode 100644 index 0000000000000..aa5a9c46e7b37 --- /dev/null +++ b/system/diagnostic_graph_aggregator/src/common/graph/names.hpp @@ -0,0 +1,42 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef COMMON__GRAPH__NAMES_HPP_ +#define COMMON__GRAPH__NAMES_HPP_ + +namespace diagnostic_graph_aggregator::unit_name +{ + +constexpr char const * link = "link"; +constexpr char const * diag = "diag"; +constexpr char const * min = "or"; +constexpr char const * max = "and"; +constexpr char const * short_circuit_max = "short-circuit-and"; +constexpr char const * warn_to_ok = "warn-to-ok"; +constexpr char const * warn_to_error = "warn-to-error"; +constexpr char const * ok = "ok"; +constexpr char const * warn = "warn"; +constexpr char const * error = "error"; +constexpr char const * stale = "stale"; + +} // namespace diagnostic_graph_aggregator::unit_name + +namespace diagnostic_graph_aggregator::edit_name +{ + +constexpr char const * remove = "remove"; + +} // namespace diagnostic_graph_aggregator::edit_name + +#endif // COMMON__GRAPH__NAMES_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/common/graph/types.hpp b/system/diagnostic_graph_aggregator/src/common/graph/types.hpp index 693094914db1d..6eae26a1f98c7 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/types.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/types.hpp @@ -17,22 +17,47 @@ #include #include +#include +#include +#include +#include +#include +#include +#include +#include #include #include #include +#include + namespace diagnostic_graph_aggregator { using diagnostic_msgs::msg::DiagnosticArray; using diagnostic_msgs::msg::DiagnosticStatus; -using tier4_system_msgs::msg::DiagnosticGraph; -using tier4_system_msgs::msg::DiagnosticLink; -using tier4_system_msgs::msg::DiagnosticNode; +using tier4_system_msgs::msg::DiagGraphStatus; +using tier4_system_msgs::msg::DiagGraphStruct; +using tier4_system_msgs::msg::DiagLeafStatus; +using tier4_system_msgs::msg::DiagLeafStruct; +using tier4_system_msgs::msg::DiagLinkStatus; +using tier4_system_msgs::msg::DiagLinkStruct; +using tier4_system_msgs::msg::DiagNodeStatus; +using tier4_system_msgs::msg::DiagNodeStruct; using DiagnosticLevel = DiagnosticStatus::_level_type; +struct PathConfig; +struct EditConfig; +struct UnitConfig; +struct LinkConfig; + +class TreeData; +class UnitLink; class BaseUnit; +class NodeUnit; class DiagUnit; +class Graph; +class UnitLoader; } // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/units.cpp b/system/diagnostic_graph_aggregator/src/common/graph/units.cpp index 6048cae85e633..da801ae078e6c 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/units.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/units.cpp @@ -14,168 +14,216 @@ #include "units.hpp" +#include "config.hpp" #include "error.hpp" +#include "loader.hpp" #include -#include -#include -#include namespace diagnostic_graph_aggregator { -using LinkList = std::vector>; +void UnitLink::initialize_object(BaseUnit * parent, BaseUnit * child) +{ + parent_ = parent; + child_ = child; +} -void merge(LinkList & a, const LinkList & b, bool uses) +void UnitLink::initialize_struct() { - for (const auto & [node, used] : b) { - a.push_back(std::make_pair(node, used && uses)); - } + struct_.parent = parent_->index(); + struct_.child = child_->index(); + struct_.is_leaf = child_->is_leaf(); } -auto resolve(const BaseUnit::NodeDict & dict, const std::vector & children) +void UnitLink::initialize_status() { - std::vector result; - for (const auto & child : children) { - result.push_back(dict.configs.at(child)); - } - return result; + // Do nothing. } -BaseUnit::BaseUnit(const std::string & path) : path_(path) +BaseUnit::BaseUnit(const UnitLoader & unit) { - index_ = 0; - level_ = DiagnosticStatus::OK; + index_ = unit.index(); + parents_ = unit.parents(); } -BaseUnit::NodeData BaseUnit::status() const +bool BaseUnit::update() { - if (path_.empty()) { - return {level_, links_}; - } else { - return {level_, {std::make_pair(this, true)}}; + // Update the level of this unit. + update_status(); + + // If the level does not change, it will not affect the parents. + const auto curr_level = level(); + if (curr_level == prev_level_) return false; + prev_level_ = curr_level; + + // If the level changes, the parents also need to be updated. + bool result = false; + for (const auto & link : parents_) { + const auto unit = link->parent(); + result = result || unit->update(); } + return result; } -BaseUnit::NodeData BaseUnit::report() const +NodeUnit::NodeUnit(const UnitLoader & unit) : BaseUnit(unit) { - return {level_, links_}; + struct_.path = unit.path(); + status_.level = DiagnosticStatus::STALE; } -void DiagUnit::init(const UnitConfig::SharedPtr & config, const NodeDict &) +void NodeUnit::initialize_struct() { - name_ = config->data.take_text("diag"); - timeout_ = config->data.take("timeout", 1.0); + struct_.type = type(); } -void DiagUnit::update(const rclcpp::Time & stamp) +void NodeUnit::initialize_status() { - if (diagnostics_) { - const auto updated = diagnostics_.value().first; - const auto elapsed = (stamp - updated).seconds(); - if (timeout_ < elapsed) { - diagnostics_ = std::nullopt; - } - } + if (child_links().size() == 0) update(); +} - if (diagnostics_) { - level_ = diagnostics_.value().second.level; - } else { - level_ = DiagnosticStatus::STALE; - } +LeafUnit::LeafUnit(const UnitLoader & unit) : BaseUnit(unit) +{ + const auto node = unit.data().required("node").text(); + const auto name = unit.data().required("name").text(); + const auto sep = node.empty() ? "" : ": "; + + struct_.path = unit.path(); + struct_.name = node + sep + name; + status_.level = DiagnosticStatus::STALE; } -void DiagUnit::callback(const rclcpp::Time & stamp, const DiagnosticStatus & status) +void LeafUnit::initialize_struct() { - diagnostics_ = std::make_pair(stamp, status); + struct_.type = type(); } -AndUnit::AndUnit(const std::string & path, bool short_circuit) : BaseUnit(path) +void LeafUnit::initialize_status() { - short_circuit_ = short_circuit; + if (child_links().size() == 0) update(); } -void AndUnit::init(const UnitConfig::SharedPtr & config, const NodeDict & dict) +DiagUnit::DiagUnit(const UnitLoader & unit) : LeafUnit(unit) { - children_ = resolve(dict, config->children); + timeout_ = unit.data().optional("timeout").real(1.0); } -void AndUnit::update(const rclcpp::Time &) +void DiagUnit::update_status() { - if (children_.empty()) { - return; - } + // Do nothing. The level is updated by on_diag and on_time. +} - bool uses = true; - level_ = DiagnosticStatus::OK; - links_ = LinkList(); +bool DiagUnit::on_diag(const rclcpp::Time & stamp, const DiagnosticStatus & status) +{ + last_updated_time_ = stamp; + status_.level = status.level; + status_.message = status.message; + status_.hardware_id = status.hardware_id; + status_.values = status.values; + return update(); +} - for (const auto & child : children_) { - const auto status = child->status(); - level_ = std::max(level_, status.level); - merge(links_, status.links, uses); - if (short_circuit_ && level_ != DiagnosticStatus::OK) { - uses = false; +bool DiagUnit::on_time(const rclcpp::Time & stamp) +{ + if (last_updated_time_) { + const auto updated = last_updated_time_.value(); + const auto elapsed = (stamp - updated).seconds(); + if (timeout_ < elapsed) { + last_updated_time_ = std::nullopt; + status_ = DiagLeafStatus(); + status_.level = DiagnosticStatus::STALE; } } - level_ = std::min(level_, DiagnosticStatus::ERROR); + return update(); } -void OrUnit::init(const UnitConfig::SharedPtr & config, const NodeDict & dict) +MaxUnit::MaxUnit(const UnitLoader & unit) : NodeUnit(unit) { - children_ = resolve(dict, config->children); + links_ = unit.children(); } -void OrUnit::update(const rclcpp::Time &) +void MaxUnit::update_status() { - if (children_.empty()) { - return; + DiagnosticLevel level = DiagnosticStatus::OK; + for (const auto & link : links_) { + level = std::max(level, link->child()->level()); } + status_.level = std::min(level, DiagnosticStatus::ERROR); +} - level_ = DiagnosticStatus::ERROR; - links_ = LinkList(); - - for (const auto & child : children_) { - const auto status = child->status(); - level_ = std::min(level_, status.level); - merge(links_, status.links, true); +void ShortCircuitMaxUnit::update_status() +{ + // TODO(Takagi, Isamu): update link flags. + DiagnosticLevel level = DiagnosticStatus::OK; + for (const auto & link : links_) { + level = std::max(level, link->child()->level()); } - level_ = std::min(level_, DiagnosticStatus::ERROR); + status_.level = std::min(level, DiagnosticStatus::ERROR); } -RemapUnit::RemapUnit(const std::string & path, DiagnosticLevel remap_warn) : BaseUnit(path) +MinUnit::MinUnit(const UnitLoader & unit) : NodeUnit(unit) { - remap_warn_ = remap_warn; + links_ = unit.children(); } -void RemapUnit::init(const UnitConfig::SharedPtr & config, const NodeDict & dict) +void MinUnit::update_status() { - if (config->children.size() != 1) { - throw error("list size must be 1", config->data); + DiagnosticLevel level = DiagnosticStatus::OK; + if (!links_.empty()) { + level = DiagnosticStatus::STALE; + for (const auto & link : links_) { + level = std::min(level, link->child()->level()); + } } - children_ = resolve(dict, config->children); + status_.level = std::min(level, DiagnosticStatus::ERROR); +} + +RemapUnit::RemapUnit(const UnitLoader & unit) : NodeUnit(unit) +{ + link_ = unit.child(); +} + +void RemapUnit::update_status() +{ + const auto level = link_->child()->level(); + status_.level = (level == level_from_) ? level_to_ : level; +} + +WarnToOkUnit::WarnToOkUnit(const UnitLoader & unit) : RemapUnit(unit) +{ + level_from_ = DiagnosticStatus::WARN; + level_to_ = DiagnosticStatus::OK; } -void RemapUnit::update(const rclcpp::Time &) +WarnToErrorUnit::WarnToErrorUnit(const UnitLoader & unit) : RemapUnit(unit) { - const auto status = children_.front()->status(); - level_ = status.level; - links_ = status.links; + level_from_ = DiagnosticStatus::WARN; + level_to_ = DiagnosticStatus::ERROR; +} - if (level_ == DiagnosticStatus::WARN) level_ = remap_warn_; +void ConstUnit::update_status() +{ + // Do nothing. This unit always returns the same level. +} + +OkUnit::OkUnit(const UnitLoader & unit) : ConstUnit(unit) +{ + status_.level = DiagnosticStatus::OK; } -DebugUnit::DebugUnit(const std::string & path, DiagnosticLevel level) : BaseUnit(path) +WarnUnit::WarnUnit(const UnitLoader & unit) : ConstUnit(unit) { - level_ = level; // overwrite + status_.level = DiagnosticStatus::WARN; } -void DebugUnit::init(const UnitConfig::SharedPtr &, const NodeDict &) +ErrorUnit::ErrorUnit(const UnitLoader & unit) : ConstUnit(unit) { + status_.level = DiagnosticStatus::ERROR; } -void DebugUnit::update(const rclcpp::Time &) +StaleUnit::StaleUnit(const UnitLoader & unit) : ConstUnit(unit) { + status_.level = DiagnosticStatus::STALE; } } // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/units.hpp b/system/diagnostic_graph_aggregator/src/common/graph/units.hpp index dce223b30f728..f478fa9ef1a2a 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/units.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/units.hpp @@ -15,120 +15,212 @@ #ifndef COMMON__GRAPH__UNITS_HPP_ #define COMMON__GRAPH__UNITS_HPP_ -#include "config.hpp" +#include "names.hpp" #include "types.hpp" #include -#include #include #include -#include -#include #include namespace diagnostic_graph_aggregator { +class UnitLink +{ +public: + void initialize_object(BaseUnit * parent, BaseUnit * child); + void initialize_struct(); + void initialize_status(); + DiagLinkStruct create_struct() const { return struct_; } + DiagLinkStatus create_status() const { return status_; } + BaseUnit * parent() const { return parent_; } + BaseUnit * child() const { return child_; } + +private: + BaseUnit * parent_; + BaseUnit * child_; + DiagLinkStruct struct_; + DiagLinkStatus status_; +}; + class BaseUnit { public: - struct NodeDict - { - std::unordered_map configs; - std::unordered_map paths; - }; - struct NodeData - { - DiagnosticLevel level; - std::vector> links; - }; - using UniquePtr = std::unique_ptr; - using UniquePtrList = std::vector>; - - explicit BaseUnit(const std::string & path); + explicit BaseUnit(const UnitLoader & unit); virtual ~BaseUnit() = default; - virtual void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) = 0; - virtual void update(const rclcpp::Time & stamp) = 0; + virtual DiagnosticLevel level() const = 0; + virtual std::string path() const = 0; virtual std::string type() const = 0; - - NodeData status() const; - NodeData report() const; - DiagnosticLevel level() const { return level_; } - - auto path() const { return path_; } - auto children() const { return children_; } - + virtual std::vector child_links() const = 0; + virtual bool is_leaf() const = 0; size_t index() const { return index_; } - void set_index(const size_t index) { index_ = index; } + size_t parent_size() const { return parents_.size(); } protected: - DiagnosticLevel level_; - std::string path_; - std::vector children_; - std::vector> links_; + bool update(); private: + virtual void update_status() = 0; size_t index_; + std::vector parents_; + std::optional prev_level_; +}; + +class NodeUnit : public BaseUnit +{ +public: + explicit NodeUnit(const UnitLoader & unit); + void initialize_struct(); + void initialize_status(); + bool is_leaf() const override { return false; } + DiagNodeStruct create_struct() const { return struct_; } + DiagNodeStatus create_status() const { return status_; } + DiagnosticLevel level() const override { return status_.level; } + std::string path() const override { return struct_.path; } + +protected: + DiagNodeStruct struct_; + DiagNodeStatus status_; }; -class DiagUnit : public BaseUnit +class LeafUnit : public BaseUnit { public: - using BaseUnit::BaseUnit; - void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; - void update(const rclcpp::Time & stamp) override; - std::string type() const override { return "diag"; } + explicit LeafUnit(const UnitLoader & unit); + void initialize_struct(); + void initialize_status(); + bool is_leaf() const override { return true; } + DiagLeafStruct create_struct() const { return struct_; } + DiagLeafStatus create_status() const { return status_; } + DiagnosticLevel level() const override { return status_.level; } + std::string name() const { return struct_.name; } + std::string path() const override { return struct_.path; } - std::string name() const { return name_; } - void callback(const rclcpp::Time & stamp, const DiagnosticStatus & status); +protected: + DiagLeafStruct struct_; + DiagLeafStatus status_; +}; + +class DiagUnit : public LeafUnit +{ +public: + explicit DiagUnit(const UnitLoader & unit); + std::string type() const override { return unit_name::diag; } + std::vector child_links() const override { return {}; } + bool on_time(const rclcpp::Time & stamp); + bool on_diag(const rclcpp::Time & stamp, const DiagnosticStatus & status); private: + void update_status() override; double timeout_; - std::optional> diagnostics_; - std::string name_; + std::optional last_updated_time_; +}; + +class MaxUnit : public NodeUnit +{ +public: + explicit MaxUnit(const UnitLoader & unit); + std::string type() const override { return unit_name::max; } + std::vector child_links() const override { return links_; } + +protected: + std::vector links_; + +private: + void update_status() override; +}; + +class ShortCircuitMaxUnit : public MaxUnit +{ +public: + using MaxUnit::MaxUnit; + std::string type() const override { return unit_name::short_circuit_max; } + +private: + void update_status() override; }; -class AndUnit : public BaseUnit +class MinUnit : public NodeUnit { public: - AndUnit(const std::string & path, bool short_circuit); - void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; - void update(const rclcpp::Time & stamp) override; - std::string type() const override { return short_circuit_ ? "short-circuit-and" : "and"; } + explicit MinUnit(const UnitLoader & unit); + std::string type() const override { return unit_name::min; } + std::vector child_links() const override { return links_; } + +protected: + std::vector links_; private: - bool short_circuit_; + void update_status() override; +}; + +class RemapUnit : public NodeUnit +{ +public: + explicit RemapUnit(const UnitLoader & unit); + std::vector child_links() const override { return {link_}; } + +protected: + UnitLink * link_; + DiagnosticLevel level_from_; + DiagnosticLevel level_to_; + +private: + void update_status() override; +}; + +class WarnToOkUnit : public RemapUnit +{ +public: + explicit WarnToOkUnit(const UnitLoader & unit); + std::string type() const override { return unit_name::warn_to_ok; } }; -class OrUnit : public BaseUnit +class WarnToErrorUnit : public RemapUnit { public: - using BaseUnit::BaseUnit; - void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; - void update(const rclcpp::Time & stamp) override; - std::string type() const override { return "or"; } + explicit WarnToErrorUnit(const UnitLoader & unit); + std::string type() const override { return unit_name::warn_to_error; } }; -class RemapUnit : public BaseUnit +class ConstUnit : public NodeUnit { public: - RemapUnit(const std::string & path, DiagnosticLevel remap_warn); - void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; - void update(const rclcpp::Time & stamp) override; - std::string type() const override { return "remap"; } + using NodeUnit::NodeUnit; + std::vector child_links() const override { return {}; } private: - DiagnosticLevel remap_warn_; + void update_status() override; +}; + +class OkUnit : public ConstUnit +{ +public: + explicit OkUnit(const UnitLoader & unit); + std::string type() const override { return unit_name::ok; } +}; + +class WarnUnit : public ConstUnit +{ +public: + explicit WarnUnit(const UnitLoader & unit); + std::string type() const override { return unit_name::warn; } +}; + +class ErrorUnit : public ConstUnit +{ +public: + explicit ErrorUnit(const UnitLoader & unit); + std::string type() const override { return unit_name::error; } }; -class DebugUnit : public BaseUnit +class StaleUnit : public ConstUnit { public: - DebugUnit(const std::string & path, DiagnosticLevel level); - void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; - void update(const rclcpp::Time & stamp) override; - std::string type() const override { return "const"; } + explicit StaleUnit(const UnitLoader & unit); + std::string type() const override { return unit_name::stale; } }; } // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/node/aggregator.cpp b/system/diagnostic_graph_aggregator/src/node/aggregator.cpp index cd16ce8e33e59..3287d30d4de18 100644 --- a/system/diagnostic_graph_aggregator/src/node/aggregator.cpp +++ b/system/diagnostic_graph_aggregator/src/node/aggregator.cpp @@ -15,6 +15,7 @@ #include "aggregator.hpp" #include +#include #include namespace diagnostic_graph_aggregator @@ -22,51 +23,78 @@ namespace diagnostic_graph_aggregator AggregatorNode::AggregatorNode() : Node("aggregator") { + const auto stamp = now(); + // Init diagnostics graph. { - const auto file = declare_parameter("graph_file"); - graph_.init(file); + const auto graph_file = declare_parameter("graph_file"); + std::ostringstream id; + id << std::hex << stamp.nanoseconds(); + graph_.create(graph_file, id.str()); } // Init plugins. if (declare_parameter("use_operation_mode_availability")) { - modes_ = std::make_unique(*this, graph_.nodes()); + modes_ = std::make_unique(*this, graph_); } // Init ros interface. { - using std::placeholders::_1; const auto qos_input = rclcpp::QoS(declare_parameter("input_qos_depth")); - const auto qos_graph = rclcpp::QoS(declare_parameter("graph_qos_depth")); - - const auto callback = std::bind(&AggregatorNode::on_diag, this, _1); + const auto qos_unknown = rclcpp::QoS(1); // TODO(Takagi, Isamu): parameter + const auto qos_struct = rclcpp::QoS(1).transient_local(); + const auto qos_status = rclcpp::QoS(declare_parameter("graph_qos_depth")); + const auto callback = std::bind(&AggregatorNode::on_diag, this, std::placeholders::_1); sub_input_ = create_subscription("/diagnostics", qos_input, callback); - pub_graph_ = create_publisher("/diagnostics_graph", qos_graph); + pub_unknown_ = create_publisher("/diagnostics_graph/unknowns", qos_unknown); + pub_struct_ = create_publisher("/diagnostics_graph/struct", qos_struct); + pub_status_ = create_publisher("/diagnostics_graph/status", qos_status); const auto rate = rclcpp::Rate(declare_parameter("rate")); timer_ = rclcpp::create_timer(this, get_clock(), rate.period(), [this]() { on_timer(); }); } - // Init debug mode. - debug_ = declare_parameter("use_debug_mode"); + // Send structure topic once. + pub_struct_->publish(graph_.create_struct(stamp)); } AggregatorNode::~AggregatorNode() { - // for unique_ptr + // For unique_ptr members. +} + +DiagnosticArray AggregatorNode::create_unknown_diags(const rclcpp::Time & stamp) +{ + DiagnosticArray msg; + msg.header.stamp = stamp; + for (const auto & [name, diag] : unknown_diags_) msg.status.push_back(diag); + return msg; } void AggregatorNode::on_timer() { + // Check timeout of diag units. const auto stamp = now(); - pub_graph_->publish(graph_.report(stamp)); - if (debug_) graph_.debug(); + graph_.update(stamp); + + // Publish status. + pub_status_->publish(graph_.create_status(stamp)); + pub_unknown_->publish(create_unknown_diags(stamp)); if (modes_) modes_->update(stamp); } -void AggregatorNode::on_diag(const DiagnosticArray::ConstSharedPtr msg) +void AggregatorNode::on_diag(const DiagnosticArray & msg) { - graph_.callback(now(), *msg); + // Update status. Store it as unknown if it does not exist in the graph. + const auto & stamp = msg.header.stamp; + for (const auto & status : msg.status) { + if (!graph_.update(stamp, status)) { + unknown_diags_[status.name] = status; + } + } + + // TODO(Takagi, Isamu): Publish immediately when graph status changes. + // pub_status_->publish(); } } // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/node/aggregator.hpp b/system/diagnostic_graph_aggregator/src/node/aggregator.hpp index 6bf9aead9754d..8a0e12edb25e5 100644 --- a/system/diagnostic_graph_aggregator/src/node/aggregator.hpp +++ b/system/diagnostic_graph_aggregator/src/node/aggregator.hpp @@ -15,13 +15,14 @@ #ifndef NODE__AGGREGATOR_HPP_ #define NODE__AGGREGATOR_HPP_ +#include "availability.hpp" #include "graph/graph.hpp" -#include "graph/types.hpp" -#include "plugin/modes.hpp" #include #include +#include +#include namespace diagnostic_graph_aggregator { @@ -34,14 +35,17 @@ class AggregatorNode : public rclcpp::Node private: Graph graph_; - std::unique_ptr modes_; + std::unique_ptr modes_; rclcpp::TimerBase::SharedPtr timer_; rclcpp::Subscription::SharedPtr sub_input_; - rclcpp::Publisher::SharedPtr pub_graph_; + rclcpp::Publisher::SharedPtr pub_unknown_; + rclcpp::Publisher::SharedPtr pub_struct_; + rclcpp::Publisher::SharedPtr pub_status_; + DiagnosticArray create_unknown_diags(const rclcpp::Time & stamp); void on_timer(); - void on_diag(const DiagnosticArray::ConstSharedPtr msg); + void on_diag(const DiagnosticArray & msg); - bool debug_; + std::unordered_map unknown_diags_; }; } // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/node/plugin/modes.cpp b/system/diagnostic_graph_aggregator/src/node/availability.cpp similarity index 66% rename from system/diagnostic_graph_aggregator/src/node/plugin/modes.cpp rename to system/diagnostic_graph_aggregator/src/node/availability.cpp index c73de86cba439..60ad418799716 100644 --- a/system/diagnostic_graph_aggregator/src/node/plugin/modes.cpp +++ b/system/diagnostic_graph_aggregator/src/node/availability.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "modes.hpp" +#include "availability.hpp" -#include "graph/config.hpp" #include "graph/error.hpp" +#include "graph/graph.hpp" #include "graph/units.hpp" #include @@ -25,38 +25,38 @@ namespace diagnostic_graph_aggregator { -OperationModes::OperationModes(rclcpp::Node & node, const std::vector & graph) +ModesAvailability::ModesAvailability(rclcpp::Node & node, const Graph & graph) { pub_ = node.create_publisher("/system/operation_mode/availability", rclcpp::QoS(1)); using PathDict = std::unordered_map; PathDict paths; - for (const auto & node : graph) { - paths[node->path()] = node; + for (const auto & unit : graph.units()) { + paths[unit->path()] = unit; } - const auto find_node = [](const PathDict & paths, const std::string & name) { + const auto find_unit = [](const PathDict & paths, const std::string & name) { const auto iter = paths.find(name); if (iter != paths.end()) { return iter->second; } - throw error("summary node is not found", name); + throw ModeNotFound(name); }; // clang-format off - stop_mode_ = find_node(paths, "/autoware/modes/stop"); - autonomous_mode_ = find_node(paths, "/autoware/modes/autonomous"); - local_mode_ = find_node(paths, "/autoware/modes/local"); - remote_mode_ = find_node(paths, "/autoware/modes/remote"); - emergency_stop_mrm_ = find_node(paths, "/autoware/modes/emergency_stop"); - comfortable_stop_mrm_ = find_node(paths, "/autoware/modes/comfortable_stop"); - pull_over_mrm_ = find_node(paths, "/autoware/modes/pull_over"); + stop_mode_ = find_unit(paths, "/autoware/modes/stop"); + autonomous_mode_ = find_unit(paths, "/autoware/modes/autonomous"); + local_mode_ = find_unit(paths, "/autoware/modes/local"); + remote_mode_ = find_unit(paths, "/autoware/modes/remote"); + emergency_stop_mrm_ = find_unit(paths, "/autoware/modes/emergency_stop"); + comfortable_stop_mrm_ = find_unit(paths, "/autoware/modes/comfortable_stop"); + pull_over_mrm_ = find_unit(paths, "/autoware/modes/pull_over"); // clang-format on } -void OperationModes::update(const rclcpp::Time & stamp) const +void ModesAvailability::update(const rclcpp::Time & stamp) const { - const auto is_ok = [](const BaseUnit * node) { return node->level() == DiagnosticStatus::OK; }; + const auto is_ok = [](const BaseUnit * unit) { return unit->level() == DiagnosticStatus::OK; }; // clang-format off Availability message; diff --git a/system/diagnostic_graph_aggregator/src/node/plugin/modes.hpp b/system/diagnostic_graph_aggregator/src/node/availability.hpp similarity index 85% rename from system/diagnostic_graph_aggregator/src/node/plugin/modes.hpp rename to system/diagnostic_graph_aggregator/src/node/availability.hpp index 1ed22c7d9d058..c91db089266f5 100644 --- a/system/diagnostic_graph_aggregator/src/node/plugin/modes.hpp +++ b/system/diagnostic_graph_aggregator/src/node/availability.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NODE__PLUGIN__MODES_HPP_ -#define NODE__PLUGIN__MODES_HPP_ +#ifndef NODE__AVAILABILITY_HPP_ +#define NODE__AVAILABILITY_HPP_ #include "graph/types.hpp" @@ -21,15 +21,13 @@ #include -#include - namespace diagnostic_graph_aggregator { -class OperationModes +class ModesAvailability { public: - OperationModes(rclcpp::Node & node, const std::vector & graph); + ModesAvailability(rclcpp::Node & node, const Graph & graph); void update(const rclcpp::Time & stamp) const; private: @@ -48,4 +46,4 @@ class OperationModes } // namespace diagnostic_graph_aggregator -#endif // NODE__PLUGIN__MODES_HPP_ +#endif // NODE__AVAILABILITY_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/node/converter.cpp b/system/diagnostic_graph_aggregator/src/node/converter.cpp deleted file mode 100644 index f0b2108374017..0000000000000 --- a/system/diagnostic_graph_aggregator/src/node/converter.cpp +++ /dev/null @@ -1,133 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "converter.hpp" - -#include - -namespace diagnostic_graph_aggregator -{ - -std::string level_to_string(DiagnosticLevel level) -{ - switch (level) { - case DiagnosticStatus::OK: - return "OK"; - case DiagnosticStatus::WARN: - return "WARN"; - case DiagnosticStatus::ERROR: - return "ERROR"; - case DiagnosticStatus::STALE: - return "STALE"; - } - return "UNKNOWN"; -} - -std::string parent_path(const std::string & path) -{ - return path.substr(0, path.rfind('/')); -} - -auto create_tree(const DiagnosticGraph & graph) -{ - std::map, std::greater> tree; - for (const auto & node : graph.nodes) { - tree.emplace(node.status.name, std::make_unique(true)); - } - for (const auto & node : graph.nodes) { - std::string path = node.status.name; - while (path = parent_path(path), !path.empty()) { - if (tree.count(path)) break; - tree.emplace(path, std::make_unique(false)); - } - } - for (const auto & [path, node] : tree) { - const auto parent = parent_path(path); - node->parent = parent.empty() ? nullptr : tree[parent].get(); - } - return tree; -} - -ConverterNode::ConverterNode() : Node("converter") -{ - using std::placeholders::_1; - const auto qos_graph = rclcpp::QoS(1); - const auto qos_array = rclcpp::QoS(1); - - const auto callback = std::bind(&ConverterNode::on_graph, this, _1); - sub_graph_ = create_subscription("/diagnostics_graph", qos_graph, callback); - pub_array_ = create_publisher("/diagnostics_agg", qos_array); - - initialize_tree_ = false; - complement_tree_ = declare_parameter("complement_tree"); -} - -void ConverterNode::on_graph(const DiagnosticGraph::ConstSharedPtr msg) -{ - DiagnosticArray message; - message.header.stamp = msg->stamp; - message.status.reserve(msg->nodes.size()); - for (const auto & node : msg->nodes) { - message.status.push_back(node.status); - for (const auto & link : node.links) { - diagnostic_msgs::msg::KeyValue kv; - const auto & status = msg->nodes[link.index].status; - kv.key = status.name; - kv.value = level_to_string(status.level); - if (link.used) { - message.status.back().values.push_back(kv); - } - } - } - - if (complement_tree_ && !initialize_tree_) { - initialize_tree_ = true; - tree_ = create_tree(*msg); - } - - if (complement_tree_) { - for (const auto & [path, node] : tree_) { - node->level = DiagnosticStatus::OK; - } - for (const auto & node : msg->nodes) { - tree_[node.status.name]->level = node.status.level; - } - for (const auto & [path, node] : tree_) { - if (!node->parent) continue; - node->parent->level = std::max(node->parent->level, node->level); - } - for (const auto & [path, node] : tree_) { - if (node->leaf) continue; - message.status.emplace_back(); - message.status.back().name = path; - message.status.back().level = node->level; - } - } - - pub_array_->publish(message); -} - -} // namespace diagnostic_graph_aggregator - -int main(int argc, char ** argv) -{ - using diagnostic_graph_aggregator::ConverterNode; - rclcpp::init(argc, argv); - rclcpp::executors::SingleThreadedExecutor executor; - auto node = std::make_shared(); - executor.add_node(node); - executor.spin(); - executor.remove_node(node); - rclcpp::shutdown(); -} diff --git a/system/diagnostic_graph_aggregator/src/tool/plantuml.cpp b/system/diagnostic_graph_aggregator/src/tool/plantuml.cpp index bfbb382a78fcb..9f7eb34bf3454 100644 --- a/system/diagnostic_graph_aggregator/src/tool/plantuml.cpp +++ b/system/diagnostic_graph_aggregator/src/tool/plantuml.cpp @@ -12,7 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "utils/loader.hpp" +#include "graph/graph.hpp" +#include "graph/units.hpp" #include @@ -21,18 +22,19 @@ namespace diagnostic_graph_aggregator void dump_root(const std::string & path) { - const auto graph = load_graph_nodes(path); - const auto color = "#FFFFFF"; + const auto color = "#EEEEEE"; + Graph graph; + graph.create(path); - for (const auto & node : graph.nodes) { - std::cout << "card " << node << " " << color << " [" << std::endl; - std::cout << node->path << std::endl; + for (const auto & unit : graph.units()) { + std::cout << "card " << unit << " " << color << " [" << std::endl; + std::cout << unit->path() << std::endl; std::cout << "]" << std::endl; } - for (const auto & node : graph.nodes) { - for (const auto & child : node->children) { - std::cout << node << " --> " << child << std::endl; + for (const auto & unit : graph.units()) { + for (const auto & link : unit->child_links()) { + std::cout << unit << " --> " << link->child() << std::endl; } } } diff --git a/system/diagnostic_graph_aggregator/src/tool/tree.cpp b/system/diagnostic_graph_aggregator/src/tool/tree.cpp index 9dbbc539b3b91..1e6fe93b18a80 100644 --- a/system/diagnostic_graph_aggregator/src/tool/tree.cpp +++ b/system/diagnostic_graph_aggregator/src/tool/tree.cpp @@ -12,47 +12,49 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "utils/loader.hpp" +#include "graph/graph.hpp" +#include "graph/units.hpp" #include namespace diagnostic_graph_aggregator { -void dump_node(const GraphNode * node, const std::string & indent = "", bool root = true) +void dump_unit(const BaseUnit * unit, const std::string & indent = "", bool root = true) { - const auto path = node->path.empty() ? "" : node->path + " "; - const auto type = "(" + node->type + ")"; + const auto path = unit->path().empty() ? "" : unit->path() + " "; + const auto type = "(" + unit->type() + ")"; std::cout << indent << "- " << path << type << std::endl; - if (root || node->parents.size() == 1) { - for (const auto child : node->children) { - dump_node(child, indent + " ", false); + if (root || unit->parent_size() == 1) { + for (const auto link : unit->child_links()) { + dump_unit(link->child(), indent + " ", false); } } } void dump_root(const std::string & path) { - const auto graph = load_graph_nodes(path); + Graph graph; + graph.create(path); - std::cout << "===== root nodes =================================" << std::endl; - for (const auto & node : graph.nodes) { - if (node->parents.size() == 0 && node->children.size() != 0) { - dump_node(node); + std::cout << "===== Top-level trees ============================" << std::endl; + for (const auto & unit : graph.units()) { + if (unit->parent_size() == 0 && unit->child_links().size() != 0) { + dump_unit(unit); } } - std::cout << "===== intermediate nodes =========================" << std::endl; - for (const auto & node : graph.nodes) { - if (node->parents.size() >= 2) { - dump_node(node); + std::cout << "===== Subtrees ===================================" << std::endl; + for (const auto & unit : graph.units()) { + if (unit->parent_size() >= 2 && unit->child_links().size() != 0) { + dump_unit(unit); } } - std::cout << "===== isolated nodes =============================" << std::endl; - for (const auto & node : graph.nodes) { - if (node->parents.size() == 0 && node->children.size() == 0) { - dump_node(node); + std::cout << "===== Isolated units =============================" << std::endl; + for (const auto & unit : graph.units()) { + if (unit->parent_size() == 0 && unit->child_links().size() == 0) { + dump_unit(unit); } } } diff --git a/system/diagnostic_graph_aggregator/src/tool/utils/loader.cpp b/system/diagnostic_graph_aggregator/src/tool/utils/loader.cpp deleted file mode 100644 index a2e6ce8b85334..0000000000000 --- a/system/diagnostic_graph_aggregator/src/tool/utils/loader.cpp +++ /dev/null @@ -1,57 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "loader.hpp" - -#include -#include - -namespace diagnostic_graph_aggregator -{ - -GraphRoot load_graph_nodes(const std::string & path) -{ - GraphRoot result; - { - std::unordered_map mapping; - Graph graph; - graph.init(path); - - for (const auto & node : graph.nodes()) { - auto data = std::make_unique(); - data->path = node->path(); - data->type = node->type(); - mapping[node] = std::move(data); - } - - for (const auto & [node, data] : mapping) { - for (const auto & link : node->children()) { - const auto parent = data.get(); - const auto child = mapping.at(link).get(); - child->parents.push_back(parent); - parent->children.push_back(child); - } - } - - for (auto & [node, data] : mapping) { - result.owner.push_back(std::move(data)); - } - for (const auto & node : result.owner) { - result.nodes.push_back(node.get()); - } - } - return result; -} - -} // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/tool/utils/loader.hpp b/system/diagnostic_graph_aggregator/src/tool/utils/loader.hpp deleted file mode 100644 index 70e01ec2a77b4..0000000000000 --- a/system/diagnostic_graph_aggregator/src/tool/utils/loader.hpp +++ /dev/null @@ -1,48 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef TOOL__UTILS__LOADER_HPP_ -#define TOOL__UTILS__LOADER_HPP_ - -#include "graph/graph.hpp" -#include "graph/types.hpp" -#include "graph/units.hpp" - -#include -#include -#include - -namespace diagnostic_graph_aggregator -{ - -struct GraphNode -{ - using UniquePtr = std::unique_ptr; - std::string type; - std::string path; - std::vector children; - std::vector parents; -}; - -struct GraphRoot -{ - std::vector owner; - std::vector nodes; -}; - -GraphRoot load_graph_nodes(const std::string & path); - -} // namespace diagnostic_graph_aggregator - -#endif // TOOL__UTILS__LOADER_HPP_ diff --git a/system/diagnostic_graph_aggregator/test/files/test1/field-not-found.yaml b/system/diagnostic_graph_aggregator/test/files/test1/field-not-found.yaml index 9e2b3708c049a..6070f690a3882 100644 --- a/system/diagnostic_graph_aggregator/test/files/test1/field-not-found.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test1/field-not-found.yaml @@ -1,2 +1,2 @@ -nodes: +units: - test-type: test-type diff --git a/system/diagnostic_graph_aggregator/test/files/test1/graph-circulation.yaml b/system/diagnostic_graph_aggregator/test/files/test1/graph-circulation.yaml index 4c014bdcec3f9..980d0670a7ccf 100644 --- a/system/diagnostic_graph_aggregator/test/files/test1/graph-circulation.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test1/graph-circulation.yaml @@ -1,4 +1,4 @@ -nodes: +units: - path: /foo/bar type: and list: diff --git a/system/diagnostic_graph_aggregator/test/files/test1/invalid-dict-type.yaml b/system/diagnostic_graph_aggregator/test/files/test1/invalid-dict-type.yaml index 6499b05ab8b7d..6c4cb8701ceea 100644 --- a/system/diagnostic_graph_aggregator/test/files/test1/invalid-dict-type.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test1/invalid-dict-type.yaml @@ -1 +1 @@ -nodes: test-object +units: test-object diff --git a/system/diagnostic_graph_aggregator/test/files/test1/invalid-list-type.yaml b/system/diagnostic_graph_aggregator/test/files/test1/invalid-list-type.yaml index 4fc5d96c08c62..34fd1436ed496 100644 --- a/system/diagnostic_graph_aggregator/test/files/test1/invalid-list-type.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test1/invalid-list-type.yaml @@ -1,3 +1,3 @@ -nodes: +units: - type: and list: test-list diff --git a/system/diagnostic_graph_aggregator/test/files/test1/path-conflict.yaml b/system/diagnostic_graph_aggregator/test/files/test1/path-conflict.yaml index ea3e536b74216..280276b7077db 100644 --- a/system/diagnostic_graph_aggregator/test/files/test1/path-conflict.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test1/path-conflict.yaml @@ -1,4 +1,4 @@ -nodes: +units: - path: /foo/bar type: and - path: /foo/bar diff --git a/system/diagnostic_graph_aggregator/test/files/test1/path-not-found.yaml b/system/diagnostic_graph_aggregator/test/files/test1/path-not-found.yaml index 6b0b10dfa94f4..f9d3021bb2a74 100644 --- a/system/diagnostic_graph_aggregator/test/files/test1/path-not-found.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test1/path-not-found.yaml @@ -1,4 +1,4 @@ -nodes: +units: - path: /foo/bar type: and - link: /foo/baz diff --git a/system/diagnostic_graph_aggregator/test/files/test1/unknown-node-type.yaml b/system/diagnostic_graph_aggregator/test/files/test1/unknown-unit-type.yaml similarity index 74% rename from system/diagnostic_graph_aggregator/test/files/test1/unknown-node-type.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/unknown-unit-type.yaml index a3d66fbfa43cb..865e535dc7173 100644 --- a/system/diagnostic_graph_aggregator/test/files/test1/unknown-node-type.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test1/unknown-unit-type.yaml @@ -1,2 +1,2 @@ -nodes: +units: - type: test-type diff --git a/system/diagnostic_graph_aggregator/test/files/test2/and.yaml b/system/diagnostic_graph_aggregator/test/files/test2/and.yaml index 0c9b651f89b2e..479a281ff9d08 100644 --- a/system/diagnostic_graph_aggregator/test/files/test2/and.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test2/and.yaml @@ -1,10 +1,12 @@ -nodes: +units: - path: output type: and list: - path: input-0 type: diag - diag: "test: input-0" + node: test + name: input-0 - path: input-1 type: diag - diag: "test: input-1" + node: test + name: input-1 diff --git a/system/diagnostic_graph_aggregator/test/files/test2/or.yaml b/system/diagnostic_graph_aggregator/test/files/test2/or.yaml index c7f37a6c32064..cb8440829891e 100644 --- a/system/diagnostic_graph_aggregator/test/files/test2/or.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test2/or.yaml @@ -1,10 +1,12 @@ -nodes: +units: - path: output type: or list: - path: input-0 type: diag - diag: "test: input-0" + node: test + name: input-0 - path: input-1 type: diag - diag: "test: input-1" + node: test + name: input-1 diff --git a/system/diagnostic_graph_aggregator/test/files/test2/warn-to-error.yaml b/system/diagnostic_graph_aggregator/test/files/test2/warn-to-error.yaml index 816bf4fd6e1bf..42eef3d976151 100644 --- a/system/diagnostic_graph_aggregator/test/files/test2/warn-to-error.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test2/warn-to-error.yaml @@ -1,7 +1,8 @@ -nodes: +units: - path: output type: warn-to-error - list: - - path: input-0 - type: diag - diag: "test: input-0" + item: + path: input-0 + type: diag + node: test + name: input-0 diff --git a/system/diagnostic_graph_aggregator/test/files/test2/warn-to-ok.yaml b/system/diagnostic_graph_aggregator/test/files/test2/warn-to-ok.yaml index 1f5cf18978e3c..90a10cfd42bc5 100644 --- a/system/diagnostic_graph_aggregator/test/files/test2/warn-to-ok.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test2/warn-to-ok.yaml @@ -1,7 +1,8 @@ -nodes: +units: - path: output type: warn-to-ok - list: - - path: input-0 - type: diag - diag: "test: input-0" + item: + path: input-0 + type: diag + node: test + name: input-0 diff --git a/system/diagnostic_graph_aggregator/test/src/test1.cpp b/system/diagnostic_graph_aggregator/test/src/test1.cpp index 48a0e1f45ce07..ea157852675ec 100644 --- a/system/diagnostic_graph_aggregator/test/src/test1.cpp +++ b/system/diagnostic_graph_aggregator/test/src/test1.cpp @@ -23,59 +23,59 @@ using namespace diagnostic_graph_aggregator; // NOLINT(build/namespaces) TEST(ConfigFile, RootNotFound) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/fake-file-name.yaml")), FileNotFound); + EXPECT_THROW(graph.create(resource("test1/fake-file-name.yaml")), FileNotFound); } TEST(ConfigFile, FileNotFound) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/file-not-found.yaml")), FileNotFound); + EXPECT_THROW(graph.create(resource("test1/file-not-found.yaml")), FileNotFound); } TEST(ConfigFile, UnknownSubstitution) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/unknown-substitution.yaml")), UnknownType); + EXPECT_THROW(graph.create(resource("test1/unknown-substitution.yaml")), UnknownSubstitution); } TEST(ConfigFile, UnknownNodeType) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/unknown-node-type.yaml")), UnknownType); + EXPECT_THROW(graph.create(resource("test1/unknown-unit-type.yaml")), UnknownUnitType); } TEST(ConfigFile, InvalidDictType) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/invalid-dict-type.yaml")), InvalidType); + EXPECT_THROW(graph.create(resource("test1/invalid-dict-type.yaml")), InvalidType); } TEST(ConfigFile, InvalidListType) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/invalid-list-type.yaml")), InvalidType); + EXPECT_THROW(graph.create(resource("test1/invalid-list-type.yaml")), InvalidType); } TEST(ConfigFile, FieldNotFound) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/field-not-found.yaml")), FieldNotFound); + EXPECT_THROW(graph.create(resource("test1/field-not-found.yaml")), FieldNotFound); } TEST(ConfigFile, PathConflict) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/path-conflict.yaml")), PathConflict); + EXPECT_THROW(graph.create(resource("test1/path-conflict.yaml")), PathConflict); } TEST(ConfigFile, PathNotFound) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/path-not-found.yaml")), PathNotFound); + EXPECT_THROW(graph.create(resource("test1/path-not-found.yaml")), PathNotFound); } TEST(ConfigFile, GraphCirculation) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/graph-circulation.yaml")), GraphStructure); + EXPECT_THROW(graph.create(resource("test1/graph-circulation.yaml")), GraphStructure); } diff --git a/system/diagnostic_graph_aggregator/test/src/test2.cpp b/system/diagnostic_graph_aggregator/test/src/test2.cpp index 1098ff9efb0db..b010994f5a1ca 100644 --- a/system/diagnostic_graph_aggregator/test/src/test2.cpp +++ b/system/diagnostic_graph_aggregator/test/src/test2.cpp @@ -56,11 +56,14 @@ DiagnosticArray create_input(const std::vector & levels) return array; }; -uint8_t get_output(const DiagnosticGraph & graph) +uint8_t get_output(const Graph & graph, const rclcpp::Time & stamp) { - for (const auto & node : graph.nodes) { - if (node.status.name == "output") { - return node.status.level; + const auto struct_nodes = graph.create_struct(stamp).nodes; + const auto status_nodes = graph.create_status(stamp).nodes; + + for (size_t i = 0; i < struct_nodes.size(); ++i) { + if (struct_nodes[i].path == "output") { + return status_nodes[i].level; } } throw std::runtime_error("output node is not found"); @@ -68,13 +71,17 @@ uint8_t get_output(const DiagnosticGraph & graph) TEST_P(GraphTest, Aggregation) { - const auto param = GetParam(); const auto stamp = rclcpp::Clock().now(); + const auto param = GetParam(); Graph graph; - graph.init(resource(param.config)); - graph.callback(stamp, create_input(param.inputs)); + graph.create(resource(param.config)); + + const auto array = create_input(param.inputs); + for (const auto & status : array.status) { + graph.update(stamp, status); + } - const auto output = get_output(graph.report(stamp)); + const auto output = get_output(graph, stamp); EXPECT_EQ(output, param.result); } diff --git a/system/diagnostic_graph_utils/CMakeLists.txt b/system/diagnostic_graph_utils/CMakeLists.txt new file mode 100644 index 0000000000000..48af5e8fc304f --- /dev/null +++ b/system/diagnostic_graph_utils/CMakeLists.txt @@ -0,0 +1,20 @@ +cmake_minimum_required(VERSION 3.14) +project(diagnostic_graph_utils) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/lib/graph.cpp + src/lib/subscription.cpp +) + +ament_auto_add_executable(dump + src/node/dump.cpp +) + +ament_auto_add_executable(converter + src/node/converter.cpp +) + +ament_auto_package() diff --git a/system/diagnostic_graph_utils/README.md b/system/diagnostic_graph_utils/README.md new file mode 100644 index 0000000000000..a06d664622bff --- /dev/null +++ b/system/diagnostic_graph_utils/README.md @@ -0,0 +1,13 @@ +# diagnostic_graph_utils + +This package is a utility for diagnostic graph published by [diagnostic_graph_aggregator](../diagnostic_graph_aggregator/README.md). + +## ROS node + +- [dump](./doc/node/dump.md) +- [converter](./doc/node/converter.md) + +## C++ library + +- [DiagGraph](./include/diagnostic_graph_utils/graph.hpp) +- [DiagGraphSubscription](./include/diagnostic_graph_utils/subscription.hpp) diff --git a/system/diagnostic_graph_utils/doc/node/converter.md b/system/diagnostic_graph_utils/doc/node/converter.md new file mode 100644 index 0000000000000..c3db547167474 --- /dev/null +++ b/system/diagnostic_graph_utils/doc/node/converter.md @@ -0,0 +1,31 @@ +# Converter tool + +This tool converts `/diagnostics_graph` to `/diagnostics_array` so it can be read by tools such as `rqt_runtime_monitor`. + +## Usage + +```bash +ros2 run diagnostic_graph_utils converter +``` + +## Examples + +Terminal 1: + +```bash +ros2 launch diagnostic_graph_aggregator example-main.launch.xml +``` + +Terminal 2: + +```bash +ros2 run diagnostic_graph_utils converter +``` + +Terminal 3: + +```bash +ros2 run rqt_runtime_monitor rqt_runtime_monitor --ros-args -r diagnostics:=diagnostics_array +``` + +![rqt_runtime_monitor](./images/rqt_runtime_monitor.png) diff --git a/system/diagnostic_graph_utils/doc/node/dump.md b/system/diagnostic_graph_utils/doc/node/dump.md new file mode 100644 index 0000000000000..090e9679676b6 --- /dev/null +++ b/system/diagnostic_graph_utils/doc/node/dump.md @@ -0,0 +1,46 @@ +# Dump tool + +This tool displays `/diagnostics_graph` in table format. + +## Usage + +```bash +ros2 run diagnostic_graph_utils dump +``` + +## Examples + +Terminal 1: + +```bash +ros2 launch diagnostic_graph_aggregator example-main.launch.xml +``` + +Terminal 2: + +```bash +ros2 run diagnostic_graph_utils dump +``` + +Output: + +```txt +|----|-------|----------------------------------|------|----------| +| No | Level | Path | Type | Children | +|----|-------|----------------------------------|------|----------| +| 1 | OK | /autoware/modes/stop | ok | | +| 2 | ERROR | /autoware/modes/autonomous | and | 8 9 | +| 3 | OK | /autoware/modes/local | and | 13 | +| 4 | OK | /autoware/modes/remote | and | 14 | +| 5 | OK | /autoware/modes/emergency_stop | ok | | +| 6 | OK | /autoware/modes/comfortable_stop | and | 9 | +| 7 | ERROR | /autoware/modes/pull_over | and | 8 9 | +| 8 | ERROR | /functions/pose_estimation | and | 10 | +| 9 | OK | /functions/obstacle_detection | or | 11 12 | +| 10 | ERROR | /sensing/lidars/top | diag | | +| 11 | OK | /sensing/lidars/front | diag | | +| 12 | OK | /sensing/radars/front | diag | | +| 13 | OK | /external/joystick_command | diag | | +| 14 | OK | /external/remote_command | diag | | + +``` diff --git a/system/diagnostic_graph_aggregator/doc/tool/images/rqt_runtime_monitor.png b/system/diagnostic_graph_utils/doc/node/images/rqt_runtime_monitor.png similarity index 100% rename from system/diagnostic_graph_aggregator/doc/tool/images/rqt_runtime_monitor.png rename to system/diagnostic_graph_utils/doc/node/images/rqt_runtime_monitor.png diff --git a/system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp b/system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp new file mode 100644 index 0000000000000..b2c6fc752e463 --- /dev/null +++ b/system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp @@ -0,0 +1,133 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef DIAGNOSTIC_GRAPH_UTILS__GRAPH_HPP_ +#define DIAGNOSTIC_GRAPH_UTILS__GRAPH_HPP_ + +#include + +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace diagnostic_graph_utils +{ + +class DiagLink; +class DiagUnit +{ +public: + using DiagnosticStatus = diagnostic_msgs::msg::DiagnosticStatus; + using DiagnosticLevel = DiagnosticStatus::_level_type; + + struct DiagChild + { + DiagLink * link; + DiagUnit * unit; + }; + + virtual DiagnosticStatus create_diagnostic_status() const = 0; + virtual DiagnosticLevel level() const = 0; + virtual std::string type() const = 0; + virtual std::string path() const = 0; + virtual std::vector children() const = 0; +}; + +class DiagLink +{ +public: + using DiagLinkStruct = tier4_system_msgs::msg::DiagLinkStruct; + using DiagLinkStatus = tier4_system_msgs::msg::DiagLinkStatus; + explicit DiagLink(const DiagLinkStruct & msg) : struct_(msg) {} + void update(const DiagLinkStatus & msg) { status_ = msg; } + +private: + DiagLinkStruct struct_; + DiagLinkStatus status_; +}; + +class DiagNode : public DiagUnit +{ +public: + using DiagNodeStruct = tier4_system_msgs::msg::DiagNodeStruct; + using DiagNodeStatus = tier4_system_msgs::msg::DiagNodeStatus; + explicit DiagNode(const DiagNodeStruct & msg) : struct_(msg) {} + void update(const DiagNodeStatus & msg) { status_ = msg; } + + DiagnosticStatus create_diagnostic_status() const override; + DiagnosticLevel level() const override { return status_.level; } + std::string type() const override { return struct_.type; } + std::string path() const override { return struct_.path; } + std::vector children() const override { return children_; } + void add_child(const DiagChild & child) { children_.push_back(child); } + +private: + DiagNodeStruct struct_; + DiagNodeStatus status_; + std::vector children_; +}; + +class DiagLeaf : public DiagUnit +{ +public: + using DiagLeafStruct = tier4_system_msgs::msg::DiagLeafStruct; + using DiagLeafStatus = tier4_system_msgs::msg::DiagLeafStatus; + explicit DiagLeaf(const DiagLeafStruct & msg) : struct_(msg) {} + void update(const DiagLeafStatus & msg) { status_ = msg; } + + DiagnosticStatus create_diagnostic_status() const override; + DiagnosticLevel level() const override { return status_.level; } + std::string type() const override { return struct_.type; } + std::string path() const override { return struct_.path; } + std::vector children() const override { return {}; } + +private: + DiagLeafStruct struct_; + DiagLeafStatus status_; +}; + +class DiagGraph +{ +public: + using DiagGraphStruct = tier4_system_msgs::msg::DiagGraphStruct; + using DiagGraphStatus = tier4_system_msgs::msg::DiagGraphStatus; + using SharedPtr = std::shared_ptr; + using ConstSharedPtr = std::shared_ptr; + void create(const DiagGraphStruct & msg); + bool update(const DiagGraphStatus & msg); + rclcpp::Time created_stamp() const { return created_stamp_; } + rclcpp::Time updated_stamp() const { return updated_stamp_; } + std::vector units() const; + std::vector nodes() const; + std::vector diags() const; + std::vector links() const; + +private: + rclcpp::Time created_stamp_; + rclcpp::Time updated_stamp_; + std::string id_; + std::vector> nodes_; + std::vector> diags_; + std::vector> links_; +}; + +} // namespace diagnostic_graph_utils + +#endif // DIAGNOSTIC_GRAPH_UTILS__GRAPH_HPP_ diff --git a/system/diagnostic_graph_utils/include/diagnostic_graph_utils/subscription.hpp b/system/diagnostic_graph_utils/include/diagnostic_graph_utils/subscription.hpp new file mode 100644 index 0000000000000..5aebde7ea3a38 --- /dev/null +++ b/system/diagnostic_graph_utils/include/diagnostic_graph_utils/subscription.hpp @@ -0,0 +1,53 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef DIAGNOSTIC_GRAPH_UTILS__SUBSCRIPTION_HPP_ +#define DIAGNOSTIC_GRAPH_UTILS__SUBSCRIPTION_HPP_ + +#include "diagnostic_graph_utils/graph.hpp" + +#include + +#include +#include + +namespace diagnostic_graph_utils +{ + +class DiagGraphSubscription +{ +public: + using CallbackType = std::function; + DiagGraphSubscription(); + DiagGraphSubscription(rclcpp::Node & node, size_t depth); + void subscribe(rclcpp::Node & node, size_t depth); + void register_create_callback(const CallbackType & callback); + void register_update_callback(const CallbackType & callback); + +private: + using DiagGraphStruct = tier4_system_msgs::msg::DiagGraphStruct; + using DiagGraphStatus = tier4_system_msgs::msg::DiagGraphStatus; + void on_struct(const DiagGraphStruct & msg); + void on_status(const DiagGraphStatus & msg); + rclcpp::Subscription::SharedPtr sub_struct_; + rclcpp::Subscription::SharedPtr sub_status_; + + DiagGraph::SharedPtr graph_; + CallbackType create_callback_; + CallbackType update_callback_; +}; + +} // namespace diagnostic_graph_utils + +#endif // DIAGNOSTIC_GRAPH_UTILS__SUBSCRIPTION_HPP_ diff --git a/system/diagnostic_graph_utils/package.xml b/system/diagnostic_graph_utils/package.xml new file mode 100644 index 0000000000000..42d44efb6697e --- /dev/null +++ b/system/diagnostic_graph_utils/package.xml @@ -0,0 +1,23 @@ + + + + diagnostic_graph_utils + 0.1.0 + The diagnostic_graph_utils package + Takagi, Isamu + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + diagnostic_msgs + rclcpp + tier4_system_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/system/diagnostic_graph_utils/src/lib/graph.cpp b/system/diagnostic_graph_utils/src/lib/graph.cpp new file mode 100644 index 0000000000000..f1177c1047bdb --- /dev/null +++ b/system/diagnostic_graph_utils/src/lib/graph.cpp @@ -0,0 +1,109 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "diagnostic_graph_utils/graph.hpp" + +namespace diagnostic_graph_utils +{ + +DiagUnit::DiagnosticStatus DiagNode::create_diagnostic_status() const +{ + DiagnosticStatus status; + status.level = level(); + status.name = path(); + return status; +} + +DiagUnit::DiagnosticStatus DiagLeaf::create_diagnostic_status() const +{ + DiagnosticStatus status; + status.level = level(); + status.name = path(); + status.message = status_.message; + status.hardware_id = status_.hardware_id; + status.values = status_.values; + return status; +} + +void DiagGraph::create(const DiagGraphStruct & msg) +{ + created_stamp_ = msg.stamp; + id_ = msg.id; + for (const auto & node : msg.nodes) nodes_.push_back(std::make_unique(node)); + for (const auto & diag : msg.diags) diags_.push_back(std::make_unique(diag)); + + const auto get_child = [this](bool is_leaf, size_t index) -> DiagUnit * { + if (is_leaf) { + return diags_.at(index).get(); + } else { + return nodes_.at(index).get(); + } + }; + + for (const auto & data : msg.links) { + DiagNode * parent = nodes_.at(data.parent).get(); + DiagUnit * child = get_child(data.is_leaf, data.child); + const auto link = links_.emplace_back(std::make_unique(data)).get(); + parent->add_child({link, child}); + } +} + +bool DiagGraph::update(const DiagGraphStatus & msg) +{ + if (id_ != msg.id) return false; + updated_stamp_ = msg.stamp; + for (size_t i = 0; i < msg.nodes.size(); ++i) nodes_[i]->update(msg.nodes[i]); + for (size_t i = 0; i < msg.diags.size(); ++i) diags_[i]->update(msg.diags[i]); + for (size_t i = 0; i < msg.links.size(); ++i) links_[i]->update(msg.links[i]); + return true; +} + +template +void extend_ptrs(std::vector & result, const std::vector> & list) +{ + for (const auto & item : list) result.push_back(item.get()); +} + +template +std::vector create_ptrs(const std::vector> & list) +{ + std::vector result; + extend_ptrs(result, list); + return result; +} + +std::vector DiagGraph::units() const +{ + std::vector result; + extend_ptrs(result, nodes_); + extend_ptrs(result, diags_); + return result; +} + +std::vector DiagGraph::nodes() const +{ + return create_ptrs(nodes_); +} + +std::vector DiagGraph::diags() const +{ + return create_ptrs(diags_); +} + +std::vector DiagGraph::links() const +{ + return create_ptrs(links_); +} + +} // namespace diagnostic_graph_utils diff --git a/system/diagnostic_graph_utils/src/lib/subscription.cpp b/system/diagnostic_graph_utils/src/lib/subscription.cpp new file mode 100644 index 0000000000000..655544c2e1f28 --- /dev/null +++ b/system/diagnostic_graph_utils/src/lib/subscription.cpp @@ -0,0 +1,67 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "diagnostic_graph_utils/subscription.hpp" + +namespace diagnostic_graph_utils +{ + +DiagGraphSubscription::DiagGraphSubscription() +{ + graph_ = std::make_shared(); +} + +DiagGraphSubscription::DiagGraphSubscription(rclcpp::Node & node, size_t depth) +{ + graph_ = std::make_shared(); + subscribe(node, depth); +} + +void DiagGraphSubscription::subscribe(rclcpp::Node & node, size_t depth) +{ + const auto qos_struct = rclcpp::QoS(1).transient_local(); + const auto qos_status = rclcpp::QoS(depth); + + sub_struct_ = node.create_subscription( + "/diagnostics_graph/struct", qos_struct, + std::bind(&DiagGraphSubscription::on_struct, this, std::placeholders::_1)); + sub_status_ = node.create_subscription( + "/diagnostics_graph/status", qos_status, + std::bind(&DiagGraphSubscription::on_status, this, std::placeholders::_1)); +} + +void DiagGraphSubscription::register_create_callback(const CallbackType & callback) +{ + create_callback_ = callback; +} + +void DiagGraphSubscription::register_update_callback(const CallbackType & callback) +{ + update_callback_ = callback; +} + +void DiagGraphSubscription::on_struct(const DiagGraphStruct & msg) +{ + graph_->create(msg); + if (create_callback_) create_callback_(graph_); +} + +void DiagGraphSubscription::on_status(const DiagGraphStatus & msg) +{ + if (graph_->update(msg)) { + if (update_callback_) update_callback_(graph_); + } +} + +} // namespace diagnostic_graph_utils diff --git a/system/diagnostic_graph_utils/src/node/converter.cpp b/system/diagnostic_graph_utils/src/node/converter.cpp new file mode 100644 index 0000000000000..e9e40fa0a0756 --- /dev/null +++ b/system/diagnostic_graph_utils/src/node/converter.cpp @@ -0,0 +1,53 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "converter.hpp" + +#include + +namespace diagnostic_graph_utils +{ + +ConverterNode::ConverterNode() : Node("converter") +{ + using std::placeholders::_1; + pub_array_ = create_publisher("/diagnostics_array", rclcpp::QoS(1)); + sub_graph_.register_update_callback(std::bind(&ConverterNode::on_update, this, _1)); + sub_graph_.subscribe(*this, 1); +} + +void ConverterNode::on_update(DiagGraph::ConstSharedPtr graph) +{ + DiagnosticArray array; + array.header.stamp = graph->updated_stamp(); + for (const auto & unit : graph->units()) { + if (unit->path().empty()) continue; + array.status.push_back(unit->create_diagnostic_status()); + } + pub_array_->publish(array); +} + +} // namespace diagnostic_graph_utils + +int main(int argc, char ** argv) +{ + using diagnostic_graph_utils::ConverterNode; + rclcpp::init(argc, argv); + rclcpp::executors::SingleThreadedExecutor executor; + auto node = std::make_shared(); + executor.add_node(node); + executor.spin(); + executor.remove_node(node); + rclcpp::shutdown(); +} diff --git a/system/diagnostic_graph_aggregator/src/node/converter.hpp b/system/diagnostic_graph_utils/src/node/converter.hpp similarity index 56% rename from system/diagnostic_graph_aggregator/src/node/converter.hpp rename to system/diagnostic_graph_utils/src/node/converter.hpp index 1f98abed4d619..09ce62d7293ec 100644 --- a/system/diagnostic_graph_aggregator/src/node/converter.hpp +++ b/system/diagnostic_graph_utils/src/node/converter.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 The Autoware Contributors +// Copyright 2024 The Autoware Contributors // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -15,41 +15,29 @@ #ifndef NODE__CONVERTER_HPP_ #define NODE__CONVERTER_HPP_ -#include "graph/types.hpp" +#include "diagnostic_graph_utils/subscription.hpp" #include -#include -#include // Use map for sorting keys. -#include -#include -#include +#include +#include -namespace diagnostic_graph_aggregator +namespace diagnostic_graph_utils { -struct TreeNode -{ - explicit TreeNode(bool leaf) : leaf(leaf) {} - bool leaf; - TreeNode * parent; - uint8_t level; -}; - class ConverterNode : public rclcpp::Node { public: ConverterNode(); private: - bool initialize_tree_; - bool complement_tree_; - std::map, std::greater> tree_; - rclcpp::Subscription::SharedPtr sub_graph_; + using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; + using DiagnosticStatus = diagnostic_msgs::msg::DiagnosticStatus; + void on_update(DiagGraph::ConstSharedPtr graph); rclcpp::Publisher::SharedPtr pub_array_; - void on_graph(const DiagnosticGraph::ConstSharedPtr msg); + DiagGraphSubscription sub_graph_; }; -} // namespace diagnostic_graph_aggregator +} // namespace diagnostic_graph_utils #endif // NODE__CONVERTER_HPP_ diff --git a/system/diagnostic_graph_utils/src/node/dump.cpp b/system/diagnostic_graph_utils/src/node/dump.cpp new file mode 100644 index 0000000000000..5fa4922dec1a5 --- /dev/null +++ b/system/diagnostic_graph_utils/src/node/dump.cpp @@ -0,0 +1,145 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "dump.hpp" + +#include +#include +#include +#include +#include +#include + +namespace diagnostic_graph_utils +{ + +DumpNode::DumpNode() : Node("dump") +{ + using std::placeholders::_1; + sub_graph_.register_create_callback(std::bind(&DumpNode::on_create, this, _1)); + sub_graph_.register_update_callback(std::bind(&DumpNode::on_update, this, _1)); + sub_graph_.subscribe(*this, 1); +} + +void DumpNode::on_create(DiagGraph::ConstSharedPtr graph) +{ + // Initialize table line information. + const std::string title_index = "No"; + const std::string title_level = "Level"; + const std::string title_path = "Path"; + const std::string title_type = "Type"; + const std::string title_link = "Children"; + + // Cache units. + const auto units = graph->units(); + + // Assign merged units index. + int table_index = 0; + for (const auto & unit : units) { + TableLine line; + line.index = ++table_index; + table_.emplace(unit, line); + } + + // Create link index text. Use text2 as a temporary variable. + for (const auto & unit : units) { + std::string links; + for (const auto & child : unit->children()) { + links += std::to_string(table_.at(child.unit).index) + " "; + } + if (!links.empty()) { + links.pop_back(); + } + table_.at(unit).text2 = links; + } + + // Calculate table cell width. + const auto width_index = std::max(title_index.length(), std::to_string(units.size()).length()); + const auto width_level = title_level.length(); + auto width_path = title_path.length(); + auto width_type = title_type.length(); + auto width_link = title_link.length(); + for (const auto & unit : units) { + const auto & line = table_.at(unit); + width_path = std::max(width_path, unit->path().length()); + width_type = std::max(width_type, unit->type().length()); + width_link = std::max(width_link, line.text2.length()); + } + + // Create table lines. + for (const auto & unit : units) { + auto & line = table_.at(unit); + std::ostringstream text1; + std::ostringstream text2; + text1 << "| " << std::right << std::setw(width_index) << line.index << " |"; + text2 << "| " << std::left << std::setw(width_path) << unit->path() << " "; + text2 << "| " << std::left << std::setw(width_type) << unit->type() << " "; + text2 << "| " << std::left << std::setw(width_link) << line.text2 << " |"; + line.text1 = text1.str() + " "; + line.text2 = " " + text2.str(); + } + + // Create table header. + { + std::ostringstream header; + header << "| " << std::left << std::setw(width_index) << title_index << " "; + header << "| " << std::left << std::setw(width_level) << title_level << " "; + header << "| " << std::left << std::setw(width_path) << title_path << " "; + header << "| " << std::left << std::setw(width_type) << title_type << " "; + header << "| " << std::left << std::setw(width_link) << title_link << " "; + header << "|"; + header_ = header.str(); + + border_ += "|" + std::string(width_index + 2, '-'); + border_ += "|" + std::string(width_level + 2, '-'); + border_ += "|" + std::string(width_path + 2, '-'); + border_ += "|" + std::string(width_type + 2, '-'); + border_ += "|" + std::string(width_link + 2, '-'); + border_ += "|"; + } +} + +void DumpNode::on_update(DiagGraph::ConstSharedPtr graph) +{ + const auto text_level = [](DiagUnit::DiagnosticLevel level) { + if (level == DiagUnit::DiagnosticStatus::OK) return "OK "; + if (level == DiagUnit::DiagnosticStatus::WARN) return "WARN "; + if (level == DiagUnit::DiagnosticStatus::ERROR) return "ERROR"; + if (level == DiagUnit::DiagnosticStatus::STALE) return "STALE"; + return "-----"; + }; + + std::cout << border_ << std::endl; + std::cout << header_ << std::endl; + std::cout << border_ << std::endl; + + for (const auto & unit : graph->units()) { + const auto & line = table_.at(unit); + std::cout << line.text1 << text_level(unit->level()) << line.text2 << std::endl; + } +} + +} // namespace diagnostic_graph_utils + +int main(int argc, char ** argv) +{ + using diagnostic_graph_utils::DumpNode; + rclcpp::init(argc, argv); + rclcpp::executors::SingleThreadedExecutor executor; + auto node = std::make_shared(); + executor.add_node(node); + executor.spin(); + executor.remove_node(node); + rclcpp::shutdown(); +} diff --git a/system/diagnostic_graph_utils/src/node/dump.hpp b/system/diagnostic_graph_utils/src/node/dump.hpp new file mode 100644 index 0000000000000..e37a1ea971bf5 --- /dev/null +++ b/system/diagnostic_graph_utils/src/node/dump.hpp @@ -0,0 +1,52 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef NODE__DUMP_HPP_ +#define NODE__DUMP_HPP_ + +#include "diagnostic_graph_utils/subscription.hpp" + +#include + +#include +#include + +namespace diagnostic_graph_utils +{ + +class DumpNode : public rclcpp::Node +{ +public: + DumpNode(); + +private: + void on_create(DiagGraph::ConstSharedPtr graph); + void on_update(DiagGraph::ConstSharedPtr graph); + DiagGraphSubscription sub_graph_; + + struct TableLine + { + int index; + std::string text1; + std::string text2; + }; + + std::unordered_map table_; + std::string header_; + std::string border_; +}; + +} // namespace diagnostic_graph_utils + +#endif // NODE__DUMP_HPP_ diff --git a/system/hazard_status_converter/package.xml b/system/hazard_status_converter/package.xml index 082aa85cba97a..35ff28998ee80 100644 --- a/system/hazard_status_converter/package.xml +++ b/system/hazard_status_converter/package.xml @@ -12,6 +12,7 @@ autoware_adapi_v1_msgs autoware_auto_system_msgs + diagnostic_graph_utils diagnostic_msgs rclcpp rclcpp_components diff --git a/system/hazard_status_converter/src/converter.cpp b/system/hazard_status_converter/src/converter.cpp index 58282306491dd..9aa354c124bba 100644 --- a/system/hazard_status_converter/src/converter.cpp +++ b/system/hazard_status_converter/src/converter.cpp @@ -17,180 +17,104 @@ #include #include -namespace -{ - -using autoware_auto_system_msgs::msg::HazardStatus; -using autoware_auto_system_msgs::msg::HazardStatusStamped; -using diagnostic_msgs::msg::DiagnosticStatus; -using tier4_system_msgs::msg::DiagnosticGraph; -using tier4_system_msgs::msg::DiagnosticNode; -using DiagnosticLevel = DiagnosticStatus::_level_type; - -enum class HazardLevel { NF, SF, LF, SPF }; - -struct TempNode -{ - const DiagnosticNode & node; - bool is_root_tree; -}; - -HazardLevel get_hazard_level(const TempNode & node, DiagnosticLevel root_mode_level) +namespace hazard_status_converter { - // Convert the level according to the table below. - // The Level other than auto mode is considered OK. - // |-------|-------------------------------| - // | Level | Root level | - // |-------|-------------------------------| - // | | OK | WARN | ERROR | STALE | - // | OK | NF | NF | NF | NF | - // | WARN | SF | LF | LF | LF | - // | ERROR | SF | LF | SPF | SPF | - // | STALE | SF | LF | SPF | SPF | - // |-------|-------------------------------| - - const auto root_level = node.is_root_tree ? root_mode_level : DiagnosticStatus::OK; - const auto node_level = node.node.status.level; - - if (node_level == DiagnosticStatus::OK) { - return HazardLevel::NF; - } - if (root_level == DiagnosticStatus::OK) { - return HazardLevel::SF; - } - if (node_level == DiagnosticStatus::WARN) { - return HazardLevel::LF; - } - if (root_level == DiagnosticStatus::WARN) { - return HazardLevel::LF; - } - return HazardLevel::SPF; -} -void set_root_tree(std::vector & nodes, int index) +Converter::Converter(const rclcpp::NodeOptions & options) : Node("converter", options) { - TempNode & node = nodes[index]; - if (node.is_root_tree) { - return; - } - - node.is_root_tree = true; - for (const auto & link : node.node.links) { - set_root_tree(nodes, link.index); - } + using std::placeholders::_1; + pub_hazard_ = create_publisher("~/hazard_status", rclcpp::QoS(1)); + sub_graph_.register_create_callback(std::bind(&Converter::on_create, this, _1)); + sub_graph_.register_update_callback(std::bind(&Converter::on_update, this, _1)); + sub_graph_.subscribe(*this, 1); } -HazardStatusStamped convert_hazard_diagnostics( - const DiagnosticGraph & graph, const std::string & root, bool ignore) +void Converter::on_create(DiagGraph::ConstSharedPtr graph) { - // Create temporary tree for conversion. - std::vector nodes; - nodes.reserve(graph.nodes.size()); - for (const auto & node : graph.nodes) { - nodes.push_back({node, false}); - } - - // Mark nodes included in the auto mode tree. - DiagnosticLevel root_mode_level = DiagnosticStatus::STALE; - if (!root.empty() && !ignore) { - for (size_t index = 0; index < nodes.size(); ++index) { - const auto & status = nodes[index].node.status; - if (status.name == root) { - set_root_tree(nodes, index); - root_mode_level = status.level; - } + const auto find_auto_mode_root = [](const DiagGraph & graph) { + for (const auto & unit : graph.units()) { + if (unit->path() == "/autoware/modes/autonomous") return unit; } - } + return static_cast(nullptr); + }; - // Calculate hazard level from node level and root level. - HazardStatusStamped hazard; - for (const auto & node : nodes) { - switch (get_hazard_level(node, root_mode_level)) { - case HazardLevel::NF: - hazard.status.diag_no_fault.push_back(node.node.status); - break; - case HazardLevel::SF: - hazard.status.diag_safe_fault.push_back(node.node.status); - break; - case HazardLevel::LF: - hazard.status.diag_latent_fault.push_back(node.node.status); - break; - case HazardLevel::SPF: - hazard.status.diag_single_point_fault.push_back(node.node.status); - break; + const auto make_auto_mode_tree = [](DiagUnit * root) { + std::unordered_set result; + std::unordered_set buffer; + if (root) { + buffer.insert(root); } - } - return hazard; -} - -} // namespace - -namespace hazard_status_converter -{ - -Converter::Converter(const rclcpp::NodeOptions & options) : Node("converter", options) -{ - pub_hazard_ = create_publisher("~/hazard_status", rclcpp::QoS(1)); - sub_graph_ = create_subscription( - "~/diagnostics_graph", rclcpp::QoS(3), - std::bind(&Converter::on_graph, this, std::placeholders::_1)); - sub_state_ = create_subscription( - "/autoware/state", rclcpp::QoS(1), - std::bind(&Converter::on_state, this, std::placeholders::_1)); - sub_mode_ = create_subscription( - "/system/operation_mode/state", rclcpp::QoS(1).transient_local(), - std::bind(&Converter::on_mode, this, std::placeholders::_1)); -} + while (!buffer.empty()) { + const auto unit = *buffer.begin(); + buffer.erase(buffer.begin()); + result.insert(unit); + for (const auto & child : unit->children()) buffer.insert(child.unit); + } + return result; + }; -void Converter::on_state(const AutowareState::ConstSharedPtr msg) -{ - state_ = msg; + auto_mode_root_ = find_auto_mode_root(*graph); + auto_mode_tree_ = make_auto_mode_tree(auto_mode_root_); } -void Converter::on_mode(const OperationMode::ConstSharedPtr msg) +void Converter::on_update(DiagGraph::ConstSharedPtr graph) { - mode_ = msg; -} + using DiagnosticStatus = diagnostic_msgs::msg::DiagnosticStatus; + using DiagnosticLevel = DiagnosticStatus::_level_type; + using HazardStatus = autoware_auto_system_msgs::msg::HazardStatus; + using HazardLevel = HazardStatus::_level_type; + + const auto get_hazard_level = [](DiagnosticLevel unit_level, DiagnosticLevel root_level) { + // Convert the level according to the table below. + // The Level other than auto mode is considered OK. + // |-------|-------------------------------| + // | Level | Root level | + // |-------|-------------------------------| + // | | OK | WARN | ERROR | STALE | + // | OK | NF | NF | NF | NF | + // | WARN | SF | LF | LF | LF | + // | ERROR | SF | LF | SPF | SPF | + // | STALE | SF | LF | SPF | SPF | + // |-------|-------------------------------| + if (unit_level == DiagnosticStatus::OK) return HazardStatus::NO_FAULT; + if (root_level == DiagnosticStatus::OK) return HazardStatus::SAFE_FAULT; + if (unit_level == DiagnosticStatus::WARN) return HazardStatus::LATENT_FAULT; + if (root_level == DiagnosticStatus::WARN) return HazardStatus::LATENT_FAULT; + return HazardStatus::SINGLE_POINT_FAULT; + }; -void Converter::on_graph(const DiagnosticGraph::ConstSharedPtr msg) -{ const auto get_system_level = [](const HazardStatus & status) { - if (!status.diag_single_point_fault.empty()) { - return HazardStatus::SINGLE_POINT_FAULT; - } - if (!status.diag_latent_fault.empty()) { - return HazardStatus::LATENT_FAULT; - } - if (!status.diag_safe_fault.empty()) { - return HazardStatus::SAFE_FAULT; - } + if (!status.diag_single_point_fault.empty()) return HazardStatus::SINGLE_POINT_FAULT; + if (!status.diag_latent_fault.empty()) return HazardStatus::LATENT_FAULT; + if (!status.diag_safe_fault.empty()) return HazardStatus::SAFE_FAULT; return HazardStatus::NO_FAULT; }; - const auto is_ignore = [this]() { - if (mode_ && state_) { - if (mode_->mode == OperationMode::AUTONOMOUS || mode_->mode == OperationMode::STOP) { - if (state_->state == AutowareState::WAITING_FOR_ROUTE) return true; - if (state_->state == AutowareState::PLANNING) return true; - } - if (state_->state == AutowareState::INITIALIZING) return true; - if (state_->state == AutowareState::FINALIZING) return true; - } - return false; + const auto get_hazards_vector = [](HazardStatus & status, HazardLevel level) { + if (level == HazardStatus::SINGLE_POINT_FAULT) return &status.diag_single_point_fault; + if (level == HazardStatus::LATENT_FAULT) return &status.diag_latent_fault; + if (level == HazardStatus::SAFE_FAULT) return &status.diag_safe_fault; + if (level == HazardStatus::NO_FAULT) return &status.diag_no_fault; + return static_cast *>(nullptr); }; - const auto get_root = [this]() { - if (mode_) { - if (mode_->mode == OperationMode::STOP) return "/autoware/modes/stop"; - if (mode_->mode == OperationMode::AUTONOMOUS) return "/autoware/modes/autonomous"; - if (mode_->mode == OperationMode::LOCAL) return "/autoware/modes/local"; - if (mode_->mode == OperationMode::REMOTE) return "/autoware/modes/remote"; - } - return ""; - }; + if (!auto_mode_root_) { + RCLCPP_ERROR_STREAM_THROTTLE(get_logger(), *get_clock(), 10000, "No auto mode unit."); + return; + } - HazardStatusStamped hazard = convert_hazard_diagnostics(*msg, get_root(), is_ignore()); - hazard.stamp = msg->stamp; + // Calculate hazard level from unit level and root level. + HazardStatusStamped hazard; + for (const auto & unit : graph->units()) { + if (unit->path().empty()) continue; + const bool is_auto_tree = auto_mode_tree_.count(unit); + const auto root_level = is_auto_tree ? auto_mode_root_->level() : DiagnosticStatus::OK; + const auto unit_level = unit->level(); + if (auto diags = get_hazards_vector(hazard.status, get_hazard_level(unit_level, root_level))) { + diags->push_back(unit->create_diagnostic_status()); + } + } + hazard.stamp = graph->updated_stamp(); hazard.status.level = get_system_level(hazard.status); hazard.status.emergency = hazard.status.level == HazardStatus::SINGLE_POINT_FAULT; hazard.status.emergency_holding = false; diff --git a/system/hazard_status_converter/src/converter.hpp b/system/hazard_status_converter/src/converter.hpp index 04e84cfb3c0c4..ad14ddde2bf5c 100644 --- a/system/hazard_status_converter/src/converter.hpp +++ b/system/hazard_status_converter/src/converter.hpp @@ -15,16 +15,12 @@ #ifndef CONVERTER_HPP_ #define CONVERTER_HPP_ +#include #include -#include -#include #include -#include -#include -#include -#include +#include namespace hazard_status_converter { @@ -35,20 +31,16 @@ class Converter : public rclcpp::Node explicit Converter(const rclcpp::NodeOptions & options); private: - using AutowareState = autoware_auto_system_msgs::msg::AutowareState; - using OperationMode = autoware_adapi_v1_msgs::msg::OperationModeState; - using DiagnosticGraph = tier4_system_msgs::msg::DiagnosticGraph; using HazardStatusStamped = autoware_auto_system_msgs::msg::HazardStatusStamped; - rclcpp::Subscription::SharedPtr sub_state_; - rclcpp::Subscription::SharedPtr sub_mode_; - rclcpp::Subscription::SharedPtr sub_graph_; + using DiagGraph = diagnostic_graph_utils::DiagGraph; + using DiagUnit = diagnostic_graph_utils::DiagUnit; + void on_create(DiagGraph::ConstSharedPtr graph); + void on_update(DiagGraph::ConstSharedPtr graph); + diagnostic_graph_utils::DiagGraphSubscription sub_graph_; rclcpp::Publisher::SharedPtr pub_hazard_; - void on_state(const AutowareState::ConstSharedPtr msg); - void on_mode(const OperationMode::ConstSharedPtr msg); - void on_graph(const DiagnosticGraph::ConstSharedPtr msg); - AutowareState::ConstSharedPtr state_; - OperationMode::ConstSharedPtr mode_; + DiagUnit * auto_mode_root_; + std::unordered_set auto_mode_tree_; }; } // namespace hazard_status_converter diff --git a/system/system_diagnostic_monitor/CMakeLists.txt b/system/system_diagnostic_monitor/CMakeLists.txt new file mode 100644 index 0000000000000..b253b5dbc0529 --- /dev/null +++ b/system/system_diagnostic_monitor/CMakeLists.txt @@ -0,0 +1,13 @@ +cmake_minimum_required(VERSION 3.14) +project(system_diagnostic_monitor) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +install(PROGRAMS + script/component_state_diagnostics.py + RENAME component_state_diagnostics + DESTINATION lib/${PROJECT_NAME} +) + +ament_auto_package(INSTALL_TO_SHARE config launch) diff --git a/system/system_diagnostic_monitor/README.md b/system/system_diagnostic_monitor/README.md new file mode 100644 index 0000000000000..94f5897076ff6 --- /dev/null +++ b/system/system_diagnostic_monitor/README.md @@ -0,0 +1,16 @@ +# system_diagnostic_monitor + +This package contains default configurations of diagnostic graph and scripts for system integration. + +## Configs + +| Name | Description | +| ------------------------------------------------- | ------------------------------------------------------------ | +| [autoware-main.yaml](./config/autoware-main.yaml) | Diagnostic graphs for basic monitoring of Autoware. | +| [autoware-psim.yaml](./config/autoware-psim.yaml) | Diagnostic graph with some units disabled for the simulator. | + +## Scripts + +| Name | Description | +| ---------------------------------------------------------------------- | --------------------------------------------------- | +| [component_state_diagnostics](./script/component_state_diagnostics.py) | Node that converts component states to diagnostics. | diff --git a/system/system_diagnostic_monitor/config/autoware-main.yaml b/system/system_diagnostic_monitor/config/autoware-main.yaml new file mode 100644 index 0000000000000..26f3fee2863d0 --- /dev/null +++ b/system/system_diagnostic_monitor/config/autoware-main.yaml @@ -0,0 +1,70 @@ +files: + - { path: $(find-pkg-share system_diagnostic_monitor)/config/map.yaml } + - { path: $(find-pkg-share system_diagnostic_monitor)/config/localization.yaml } + - { path: $(find-pkg-share system_diagnostic_monitor)/config/planning.yaml } + - { path: $(find-pkg-share system_diagnostic_monitor)/config/perception.yaml } + - { path: $(find-pkg-share system_diagnostic_monitor)/config/control.yaml } + - { path: $(find-pkg-share system_diagnostic_monitor)/config/vehicle.yaml } + - { path: $(find-pkg-share system_diagnostic_monitor)/config/system.yaml } + +units: + - path: /autoware/modes/stop + type: ok + + - path: /autoware/modes/autonomous + type: and + list: + - { type: link, link: /autoware/map } + - { type: link, link: /autoware/localization } + - { type: link, link: /autoware/planning } + - { type: link, link: /autoware/perception } + - { type: link, link: /autoware/control } + - { type: link, link: /autoware/vehicle } + - { type: link, link: /autoware/system } + + - path: /autoware/modes/local + type: and + list: + - { type: link, link: /autoware/vehicle } + - { type: link, link: /autoware/system } + - { type: link, link: /autoware/control/local } + + - path: /autoware/modes/remote + type: and + list: + - { type: link, link: /autoware/vehicle } + - { type: link, link: /autoware/system } + - { type: link, link: /autoware/control/remote } + + - path: /autoware/modes/emergency_stop + type: and + list: + - { type: link, link: /autoware/vehicle } + - { type: link, link: /autoware/system } + + - path: /autoware/modes/comfortable_stop + type: and + list: + - { type: link, link: /autoware/map } + - { type: link, link: /autoware/localization } + - { type: link, link: /autoware/planning } + - { type: link, link: /autoware/perception } + - { type: link, link: /autoware/control } + - { type: link, link: /autoware/vehicle } + - { type: link, link: /autoware/system } + + - path: /autoware/modes/pull_over + type: and + list: + - { type: link, link: /autoware/map } + - { type: link, link: /autoware/localization } + - { type: link, link: /autoware/planning } + - { type: link, link: /autoware/perception } + - { type: link, link: /autoware/control } + - { type: link, link: /autoware/vehicle } + - { type: link, link: /autoware/system } + + - path: /autoware/debug/tools + type: and + list: + - { type: link, link: /autoware/system/service_log_checker } diff --git a/system/system_diagnostic_monitor/config/autoware-psim.yaml b/system/system_diagnostic_monitor/config/autoware-psim.yaml new file mode 100644 index 0000000000000..6962607f912b3 --- /dev/null +++ b/system/system_diagnostic_monitor/config/autoware-psim.yaml @@ -0,0 +1,11 @@ +files: + - { path: $(find-pkg-share system_diagnostic_monitor)/config/autoware-main.yaml } + +edits: + - { type: remove, path: /autoware/map/topic_rate_check/pointcloud_map } + - { type: remove, path: /autoware/localization/matching_score } + - { type: remove, path: /autoware/localization/accuracy } + - { type: remove, path: /autoware/localization/sensor_fusion_status } + - { type: remove, path: /autoware/localization/topic_rate_check/pose_twist_fusion } + - { type: remove, path: /autoware/perception/topic_rate_check/pointcloud } + - { type: remove, path: /autoware/control/emergency_braking } diff --git a/system/system_diagnostic_monitor/config/control.yaml b/system/system_diagnostic_monitor/config/control.yaml new file mode 100644 index 0000000000000..57bf1b86c2bfc --- /dev/null +++ b/system/system_diagnostic_monitor/config/control.yaml @@ -0,0 +1,73 @@ +units: + - path: /autoware/control + type: and + list: + - { type: link, link: /autoware/control/topic_rate_check/trajectory_follower } + - { type: link, link: /autoware/control/topic_rate_check/control_command } + - { type: link, link: /autoware/control/node_alive_monitoring/vehicle_cmd_gate } + - { type: link, link: /autoware/control/emergency_braking } + - { type: link, link: /autoware/control/performance_monitoring/lane_departure } + - { type: link, link: /autoware/control/performance_monitoring/trajectory_deviation } + - { type: link, link: /autoware/control/performance_monitoring/control_state } + + - path: /autoware/control/local + type: and + list: + - { type: link, link: /autoware/control/topic_rate_check/selector } + - { type: link, link: /autoware/control/topic_rate_check/local } + + - path: /autoware/control/remote + type: and + list: + - { type: link, link: /autoware/control/topic_rate_check/selector } + - { type: link, link: /autoware/control/topic_rate_check/remote } + + - path: /autoware/control/topic_rate_check/trajectory_follower + type: diag + node: topic_state_monitor_trajectory_follower_control_cmd + name: control_topic_status + + - path: /autoware/control/topic_rate_check/control_command + type: diag + node: topic_state_monitor_control_command_control_cmd + name: control_topic_status + + - path: /autoware/control/node_alive_monitoring/vehicle_cmd_gate + type: diag + node: vehicle_cmd_gate + name: heartbeat + + - path: /autoware/control/emergency_braking + type: diag + node: autonomous_emergency_braking + name: aeb_emergency_stop + + - path: /autoware/control/performance_monitoring/lane_departure + type: diag + node: lane_departure_checker_node + name: lane_departure + + - path: /autoware/control/performance_monitoring/trajectory_deviation + type: diag + node: lane_departure_checker_node + name: trajectory_deviation + + - path: /autoware/control/performance_monitoring/control_state + type: diag + node: controller_node_exe + name: control_state + + - path: /autoware/control/topic_rate_check/selector + type: diag + node: external_cmd_selector + name: heartbeat + + - path: /autoware/control/topic_rate_check/local + type: diag + node: joy_controller + name: joy_controller_connection + + - path: /autoware/control/topic_rate_check/remote + type: diag + node: external_cmd_converter + name: remote_control_topic_status diff --git a/system/system_diagnostic_monitor/config/hardware.yaml b/system/system_diagnostic_monitor/config/hardware.yaml new file mode 100644 index 0000000000000..d73f723670f98 --- /dev/null +++ b/system/system_diagnostic_monitor/config/hardware.yaml @@ -0,0 +1,121 @@ +# TODO(Takagi, Isamu): This file is under construction. +units: + - path: /autoware/system/resources/clock/offset + diag: ": NTP Offset" + timeout: 10.0 + + - path: /autoware/system/resources/cpu/offset + diag: ": CPU Temperature" + timeout: 3.0 + + - path: /autoware/system/resources/cpu/usage + diag: ": CPU Usage" + timeout: 3.0 + + - path: /autoware/system/resources/cpu/thermal_throttling + diag: ": CPU Thermal Throttling" + timeout: 3.0 + + - path: /autoware/system/resources/cpu/frequency + diag: ": CPU Frequency" + timeout: 3.0 + + - path: /autoware/system/resources/cpu/load_average + diag: ": CPU Load Average" + timeout: 3.0 + + - path: /autoware/system/resources/gpu/temperature + diag: ": GPU Temperature" + timeout: 3.0 + + - path: /autoware/system/resources/gpu/usage + diag: ": GPU Usage" + timeout: 3.0 + + - path: /autoware/system/resources/gpu/memory_usage + diag: ": GPU Memory Usage" + timeout: 3.0 + + - path: /autoware/system/resources/gpu/thermal_throttling + diag: ": GPU Thermal Throttling" + timeout: 3.0 + + - path: /autoware/system/resources/gpu/frequency + diag: ": GPU Frequency" + timeout: 3.0 + + - path: /autoware/system/resources/memory/usage + diag: ": Memory Usage" + timeout: 3.0 + + - path: /autoware/system/resources/network/usage + diag: ": Network Usage" + timeout: 3.0 + + - path: /autoware/system/resources/network/traffic + diag: ": Network Traffic" + timeout: 3.0 + + - path: /autoware/system/resources/network/crc + diag: ": Network CRC Error" + timeout: 3.0 + + - path: /autoware/system/resources/network/packet_reassembles + diag: ": IP Packet Reassembles Failed" + timeout: 3.0 + + - path: /autoware/system/resources/storage/temperature + diag: ": HDD Temperature" + timeout: 3.0 + + - path: /autoware/system/resources/storage/recovered_error + diag: ": HDD RecoveredError" + timeout: 3.0 + + - path: /autoware/system/resources/storage/read_data_rate + diag: ": HDD ReadDataRate" + timeout: 3.0 + + - path: /autoware/system/resources/storage/write_data_rate + diag: ": HDD WriteDataRate" + timeout: 3.0 + + - path: /autoware/system/resources/storage/read_iops + diag: ": HDD ReadIOPS" + timeout: 3.0 + + - path: /autoware/system/resources/storage/write_iops + diag: ": HDD WriteIOPS" + timeout: 3.0 + + - path: /autoware/system/resources/storage/usage + diag: ": HDD Usage" + timeout: 3.0 + + - path: /autoware/system/resources/storage/power_on_hours + diag: ": HDD PowerOnHours" + timeout: 3.0 + + - path: /autoware/system/resources/storage/total_data_written + diag: ": HDD TotalDataWritten" + timeout: 3.0 + + - path: /autoware/system/resources/storage/connection + diag: ": HDD Connection" + timeout: 3.0 + + - path: /autoware/system/resources/process/high_load + diag: ": High-load" + timeout: 3.0 + + - path: /autoware/system/resources/process/high_mem + diag: ": High-mem" + timeout: 3.0 + + - path: /autoware/system/resources/process/tasks_summary + diag: ": Tasks Summary" + timeout: 3.0 + + - path: /autoware/system/resources/voltage/battery + diag: ": CMOS Battery Status" + timeout: 3.0 diff --git a/system/system_diagnostic_monitor/config/localization.yaml b/system/system_diagnostic_monitor/config/localization.yaml new file mode 100644 index 0000000000000..334101875aba6 --- /dev/null +++ b/system/system_diagnostic_monitor/config/localization.yaml @@ -0,0 +1,43 @@ +units: + - path: /autoware/localization + type: short-circuit-and + list: + - type: link + link: /autoware/localization/state + - type: and + list: + - { type: link, link: /autoware/localization/topic_rate_check/transform } + - { type: link, link: /autoware/localization/topic_rate_check/pose_twist_fusion } + - { type: link, link: /autoware/localization/matching_score } + - { type: link, link: /autoware/localization/accuracy } + - { type: link, link: /autoware/localization/sensor_fusion_status } + + - path: /autoware/localization/state + type: diag + node: component_state_diagnostics + name: localization_state + + - path: /autoware/localization/topic_rate_check/transform + type: diag + node: topic_state_monitor_transform_map_to_base_link + name: localization_topic_status + + - path: /autoware/localization/topic_rate_check/pose_twist_fusion + type: diag + node: topic_state_monitor_pose_twist_fusion_filter_pose + name: localization_topic_status + + - path: /autoware/localization/matching_score + type: diag + node: "" + name: ndt_scan_matcher + + - path: /autoware/localization/accuracy + type: diag + node: localization + name: localization_error_monitor + + - path: /autoware/localization/sensor_fusion_status + type: diag + node: localization + name: ekf_localizer diff --git a/system/system_diagnostic_monitor/config/map.yaml b/system/system_diagnostic_monitor/config/map.yaml new file mode 100644 index 0000000000000..45c1db294119f --- /dev/null +++ b/system/system_diagnostic_monitor/config/map.yaml @@ -0,0 +1,16 @@ +units: + - path: /autoware/map + type: and + list: + - { type: link, link: /autoware/map/topic_rate_check/vector_map } + - { type: link, link: /autoware/map/topic_rate_check/pointcloud_map } + + - path: /autoware/map/topic_rate_check/vector_map + type: diag + node: topic_state_monitor_vector_map + name: map_topic_status + + - path: /autoware/map/topic_rate_check/pointcloud_map + type: diag + node: topic_state_monitor_pointcloud_map + name: map_topic_status" diff --git a/system/system_diagnostic_monitor/config/perception.yaml b/system/system_diagnostic_monitor/config/perception.yaml new file mode 100644 index 0000000000000..24e3c4eed5295 --- /dev/null +++ b/system/system_diagnostic_monitor/config/perception.yaml @@ -0,0 +1,16 @@ +units: + - path: /autoware/perception + type: and + list: + - { type: link, link: /autoware/perception/topic_rate_check/objects } + - { type: link, link: /autoware/perception/topic_rate_check/pointcloud } + + - path: /autoware/perception/topic_rate_check/objects + type: diag + node: topic_state_monitor_object_recognition_objects + name: perception_topic_status + + - path: /autoware/perception/topic_rate_check/pointcloud + type: diag + node: topic_state_monitor_obstacle_segmentation_pointcloud + name: perception_topic_status diff --git a/system/system_diagnostic_monitor/config/planning.yaml b/system/system_diagnostic_monitor/config/planning.yaml new file mode 100644 index 0000000000000..c403fec2371c3 --- /dev/null +++ b/system/system_diagnostic_monitor/config/planning.yaml @@ -0,0 +1,90 @@ +units: + - path: /autoware/planning + type: short-circuit-and + list: + - type: link + link: /autoware/planning/routing/state + - type: and + list: + - { type: link, link: /autoware/planning/topic_rate_check/route } + - { type: link, link: /autoware/planning/topic_rate_check/trajectory } + - { type: link, link: /autoware/planning/trajectory_validation } + + - path: /autoware/planning/trajectory_validation + type: and + list: + - { type: link, link: /autoware/planning/trajectory_validation/finite } + - { type: link, link: /autoware/planning/trajectory_validation/interval } + - { type: link, link: /autoware/planning/trajectory_validation/curvature } + - { type: link, link: /autoware/planning/trajectory_validation/angle } + - { type: link, link: /autoware/planning/trajectory_validation/lateral_acceleration } + - { type: link, link: /autoware/planning/trajectory_validation/acceleration } + - { type: link, link: /autoware/planning/trajectory_validation/deceleration } + - { type: link, link: /autoware/planning/trajectory_validation/steering } + - { type: link, link: /autoware/planning/trajectory_validation/steering_rate } + - { type: link, link: /autoware/planning/trajectory_validation/velocity_deviation } + + - path: /autoware/planning/routing/state + type: diag + node: component_state_diagnostics + name: route_state + + - path: /autoware/planning/topic_rate_check/route + type: diag + node: topic_state_monitor_mission_planning_route + name: planning_topic_status + + - path: /autoware/planning/topic_rate_check/trajectory + type: diag + node: topic_state_monitor_scenario_planning_trajectory + name: planning_topic_status + + - path: /autoware/planning/trajectory_validation/finite + type: diag + node: planning_validator + name: trajectory_validation_finite + + - path: /autoware/planning/trajectory_validation/interval + type: diag + node: planning_validator + name: trajectory_validation_interval + + - path: /autoware/planning/trajectory_validation/curvature + type: diag + node: planning_validator + name: trajectory_validation_curvature + + - path: /autoware/planning/trajectory_validation/angle + type: diag + node: planning_validator + name: trajectory_validation_relative_angle + + - path: /autoware/planning/trajectory_validation/lateral_acceleration + type: diag + node: planning_validator + name: trajectory_validation_lateral_acceleration + + - path: /autoware/planning/trajectory_validation/acceleration + type: diag + node: planning_validator + name: trajectory_validation_acceleration + + - path: /autoware/planning/trajectory_validation/deceleration + type: diag + node: planning_validator + name: trajectory_validation_deceleration + + - path: /autoware/planning/trajectory_validation/steering + type: diag + node: planning_validator + name: trajectory_validation_steering + + - path: /autoware/planning/trajectory_validation/steering_rate + type: diag + node: planning_validator + name: trajectory_validation_steering_rate + + - path: /autoware/planning/trajectory_validation/velocity_deviation + type: diag + node: planning_validator + name: trajectory_validation_velocity_deviation diff --git a/system/system_diagnostic_monitor/config/system.yaml b/system/system_diagnostic_monitor/config/system.yaml new file mode 100644 index 0000000000000..cb96c2cd7f276 --- /dev/null +++ b/system/system_diagnostic_monitor/config/system.yaml @@ -0,0 +1,27 @@ +units: + - path: /autoware/system + type: and + list: + - { type: link, link: /autoware/system/duplicated_node_checker } + - { type: link, link: /autoware/system/topic_rate_check/emergency_control_command } + - { type: link, link: /autoware/system/emergency_stop_operation } + + - path: /autoware/system/duplicated_node_checker + type: diag + node: duplicated_node_checker + name: duplicated_node_checker + + - path: /autoware/system/service_log_checker + type: diag + node: service_log_checker + name: response_status + + - path: /autoware/system/topic_rate_check/emergency_control_command + type: diag + node: topic_state_monitor_system_emergency_control_cmd + name: system_topic_status + + - path: /autoware/system/emergency_stop_operation + type: diag + node: vehicle_cmd_gate + name: emergency_stop_operation diff --git a/system/system_diagnostic_monitor/config/vehicle.yaml b/system/system_diagnostic_monitor/config/vehicle.yaml new file mode 100644 index 0000000000000..e040e3c3c305e --- /dev/null +++ b/system/system_diagnostic_monitor/config/vehicle.yaml @@ -0,0 +1,16 @@ +units: + - path: /autoware/vehicle + type: and + list: + - { type: link, link: /autoware/vehicle/topic_rate_check/velocity } + - { type: link, link: /autoware/vehicle/topic_rate_check/steering } + + - path: /autoware/vehicle/topic_rate_check/velocity + type: diag + node: topic_state_monitor_vehicle_status_velocity_status + name: vehicle_topic_status + + - path: /autoware/vehicle/topic_rate_check/steering + type: diag + node: topic_state_monitor_vehicle_status_steering_status + name: vehicle_topic_status diff --git a/system/system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml b/system/system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml new file mode 100644 index 0000000000000..b00fcb8a26f68 --- /dev/null +++ b/system/system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml @@ -0,0 +1,7 @@ + + + + + + + diff --git a/system/system_diagnostic_monitor/package.xml b/system/system_diagnostic_monitor/package.xml new file mode 100644 index 0000000000000..a54a3dd0d109a --- /dev/null +++ b/system/system_diagnostic_monitor/package.xml @@ -0,0 +1,25 @@ + + + + system_diagnostic_monitor + 0.1.0 + The system_diagnostic_monitor package + Takagi, Isamu + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + autoware_adapi_v1_msgs + diagnostic_graph_aggregator + diagnostic_msgs + rclpy + tier4_system_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/system/system_diagnostic_monitor/script/component_state_diagnostics.py b/system/system_diagnostic_monitor/script/component_state_diagnostics.py new file mode 100755 index 0000000000000..9117f818e60fd --- /dev/null +++ b/system/system_diagnostic_monitor/script/component_state_diagnostics.py @@ -0,0 +1,102 @@ +#!/usr/bin/env python3 + +# Copyright 2023 The Autoware Contributors +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from autoware_adapi_v1_msgs.msg import LocalizationInitializationState as LocalizationState +from autoware_adapi_v1_msgs.msg import RouteState +from diagnostic_msgs.msg import DiagnosticArray +from diagnostic_msgs.msg import DiagnosticStatus +import rclpy +import rclpy.node +import rclpy.qos +import rclpy.time + + +class ComponentStateDiagnostics: + def __init__(self, node, diag_name, topic_name, topic_type, topic_qos, diag_func): + self.node = node + self.name = diag_name + self.func = diag_func + self.sub = node.create_subscription(topic_type, topic_name, self.callback, topic_qos) + self.level = DiagnosticStatus.STALE + self.stamp = None + + def callback(self, msg): + self.level = DiagnosticStatus.OK if self.func(msg) else DiagnosticStatus.ERROR + self.stamp = self.node.get_clock().now() + + def update(self, stamp): + if self.stamp: + elapsed = (stamp - self.stamp).nanoseconds * 1e-9 + if 3.0 < elapsed: + self.level = DiagnosticStatus.STALE + self.stamp = None + + def message(self): + status = DiagnosticStatus() + status.name = self.name + status.level = self.level + return status + + +class ComponentStateDiagnosticsNode(rclpy.node.Node): + def __init__(self): + super().__init__("component_state_diagnostics") + durable_qos = rclpy.qos.QoSProfile( + depth=1, + durability=rclpy.qos.DurabilityPolicy.TRANSIENT_LOCAL, + reliability=rclpy.qos.ReliabilityPolicy.RELIABLE, + ) + + self.timer = self.create_timer(0.5, self.on_timer) + self.pub = self.create_publisher(DiagnosticArray, "/diagnostics", 1) + self.states = [] + self.states.append( + ComponentStateDiagnostics( + self, + "component_state_diagnostics: localization_state", + "/api/localization/initialization_state", + LocalizationState, + durable_qos, + lambda msg: msg.state == LocalizationState.INITIALIZED, + ) + ) + self.states.append( + ComponentStateDiagnostics( + self, + "component_state_diagnostics: route_state", + "/api/routing/state", + RouteState, + durable_qos, + lambda msg: msg.state != RouteState.UNSET, + ) + ) + + def on_timer(self): + stamp = self.get_clock().now() + array = DiagnosticArray() + array.header.stamp = stamp.to_msg() + for state in self.states: + array.status.append(state.message()) + self.pub.publish(array) + + +if __name__ == "__main__": + try: + rclpy.init() + rclpy.spin(ComponentStateDiagnosticsNode()) + rclpy.shutdown() + except KeyboardInterrupt: + pass diff --git a/tools/rqt_diagnostic_graph_monitor/CMakeLists.txt b/tools/rqt_diagnostic_graph_monitor/CMakeLists.txt new file mode 100644 index 0000000000000..9e8bb20bb92a3 --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/CMakeLists.txt @@ -0,0 +1,9 @@ +cmake_minimum_required(VERSION 3.14) +project(rqt_diagnostic_graph_monitor) + +find_package(autoware_cmake REQUIRED) +autoware_package() +ament_python_install_package(${PROJECT_NAME} PACKAGE_DIR python) +install(FILES plugin.xml DESTINATION share/${PROJECT_NAME}) +install(PROGRAMS script/rqt_diagnostic_graph_monitor DESTINATION lib/${PROJECT_NAME}) +ament_auto_package(INSTALL_TO_SHARE script) diff --git a/tools/rqt_diagnostic_graph_monitor/README.md b/tools/rqt_diagnostic_graph_monitor/README.md new file mode 100644 index 0000000000000..8dccca34db8c5 --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/README.md @@ -0,0 +1 @@ +# System diagnostic monitor diff --git a/tools/rqt_diagnostic_graph_monitor/package.xml b/tools/rqt_diagnostic_graph_monitor/package.xml new file mode 100644 index 0000000000000..60780e2794998 --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/package.xml @@ -0,0 +1,24 @@ + + + + rqt_diagnostic_graph_monitor + 0.1.0 + The rqt_diagnostic_graph_monitor package + Takagi, Isamu + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + python_qt_binding + rqt_gui + rqt_gui_py + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + + diff --git a/tools/rqt_diagnostic_graph_monitor/plugin.xml b/tools/rqt_diagnostic_graph_monitor/plugin.xml new file mode 100644 index 0000000000000..6c64185e3f0af --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/plugin.xml @@ -0,0 +1,16 @@ + + + + + + + + folder + + + + utilities-system-monitor + + + + diff --git a/tools/rqt_diagnostic_graph_monitor/python/__init__.py b/tools/rqt_diagnostic_graph_monitor/python/__init__.py new file mode 100644 index 0000000000000..10f125fa447b5 --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/python/__init__.py @@ -0,0 +1,37 @@ +# Copyright 2023 The Autoware Contributors +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from rqt_gui_py.plugin import Plugin + +from .module import MonitorModule +from .widget import MonitorWidget + + +class MonitorPlugin(Plugin): + def __init__(self, context): + super().__init__(context) + self.widget = MonitorWidget() + self.module = MonitorModule(context.node) + self.module.append_struct_callback(self.widget.on_graph) + context.add_widget(self.widget) + + def shutdown_plugin(self): + self.module.shutdown() + self.widget.shutdown() + + def save_settings(self, plugin_settings, instance_settings): + pass + + def restore_settings(self, plugin_settings, instance_settings): + pass diff --git a/tools/rqt_diagnostic_graph_monitor/python/graph.py b/tools/rqt_diagnostic_graph_monitor/python/graph.py new file mode 100644 index 0000000000000..cea81c1226637 --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/python/graph.py @@ -0,0 +1,127 @@ +# Copyright 2023 The Autoware Contributors +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from diagnostic_msgs.msg import DiagnosticStatus +from rclpy.time import Time + + +class DummyStatus: + def __init__(self): + self.level = DiagnosticStatus.STALE + + +class BaseUnit: + def __init__(self, status=DummyStatus()): + self._parents = [] + self._children = [] + self._path = None + self._type = None + self._status = status + + @property + def parents(self): + return self._parents + + @property + def children(self): + return self._children + + @property + def path(self): + return self._path + + @property + def kind(self): + return self._type + + +class NodeUnit(BaseUnit): + def __init__(self, struct): + super().__init__() + self._path = struct.path + self._type = struct.type + + def update(self, status): + self._status = status + + @property + def level(self): + return self._status.level + + +class DiagUnit(BaseUnit): + def __init__(self, struct): + super().__init__() + self._path = struct.path + self._name = struct.name + self._type = "diag" + + def update(self, status): + self._status = status + + @property + def level(self): + return self._status.level + + +class UnitLink: + def __init__(self, parent: BaseUnit, child: BaseUnit): + self._parent = parent + self._child = child + parent._children.append(self) + child._parents.append(self) + + def update(self, status): + self.status = status + + @property + def parent(self): + return self._parent + + @property + def child(self): + return self._child + + +class Graph: + def __init__(self, msg): + self._struct_stamp = Time.from_msg(msg.stamp) + self._status_stamp = None + self._id = msg.id + self._nodes = [NodeUnit(struct) for struct in msg.nodes] + self._diags = [DiagUnit(struct) for struct in msg.diags] + self._units = self._nodes + self._diags + self._links = [] + for struct in msg.links: + units = self._diags if struct.is_leaf else self._nodes + nodes = self._nodes + self._links.append(UnitLink(nodes[struct.parent], units[struct.child])) + + def update(self, msg): + if msg.id == self._id: + self._status_stamp = Time.from_msg(msg.stamp) + for node, status in zip(self._nodes, msg.nodes): + node.update(status) + for diag, status in zip(self._diags, msg.diags): + diag.update(status) + for link, status in zip(self._links, msg.links): + link.update(status) + + @property + def units(self): + return self._units + + @property + def links(self): + return self._links diff --git a/tools/rqt_diagnostic_graph_monitor/python/items.py b/tools/rqt_diagnostic_graph_monitor/python/items.py new file mode 100644 index 0000000000000..96f60ef0e09cf --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/python/items.py @@ -0,0 +1,54 @@ +# Copyright 2024 The Autoware Contributors +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + + +from diagnostic_msgs.msg import DiagnosticStatus +from python_qt_binding import QtGui +from python_qt_binding import QtWidgets + +from .graph import BaseUnit +from .graph import UnitLink + + +class MonitorIcons: + def __init__(self): + self.disable = QtGui.QIcon.fromTheme("dialog-question") + self.unknown = QtGui.QIcon.fromTheme("system-search") + self.ok = QtGui.QIcon.fromTheme("emblem-default") + self.warn = QtGui.QIcon.fromTheme("emblem-important") + self.error = QtGui.QIcon.fromTheme("dialog-error") + self.stale = QtGui.QIcon.fromTheme("appointment-missed") + + self._levels = {} + self._levels[DiagnosticStatus.OK] = self.ok + self._levels[DiagnosticStatus.WARN] = self.warn + self._levels[DiagnosticStatus.ERROR] = self.error + self._levels[DiagnosticStatus.STALE] = self.stale + + def get(self, level): + return self._levels.get(level, self.unknown) + + +class MonitorItem: + icons = MonitorIcons() + + def __init__(self, link: UnitLink, unit: BaseUnit): + item_text = f"{unit.path} ({unit.kind})" if unit.path else f"({unit.kind})" + self.item = QtWidgets.QTreeWidgetItem([item_text]) + self.link = link + self.unit = unit + self.item.setIcon(0, self.icons.stale) + + def update(self): + self.item.setIcon(0, self.icons.get(self.unit.level)) diff --git a/tools/rqt_diagnostic_graph_monitor/python/module.py b/tools/rqt_diagnostic_graph_monitor/python/module.py new file mode 100644 index 0000000000000..74294659ef61a --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/python/module.py @@ -0,0 +1,61 @@ +# Copyright 2023 The Autoware Contributors +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + + +from rclpy.node import Node +from tier4_system_msgs.msg import DiagGraphStatus +from tier4_system_msgs.msg import DiagGraphStruct + +from .graph import Graph +from .utils import default_qos +from .utils import durable_qos +from .utils import foreach + + +class MonitorModule: + def __init__(self, node: Node): + self.graph = None + self.struct_callbacks = [] + self.status_callbacks = [] + self.node = node + self.sub_struct = self.subscribe_struct() + self.sub_status = self.subscribe_status() + + def append_struct_callback(self, callback): + self.struct_callbacks.append(callback) + + def append_status_callback(self, callback): + self.status_callbacks.append(callback) + + def on_struct(self, msg): + self.graph = Graph(msg) + foreach(self.struct_callbacks, lambda callback: callback(self.graph)) + + def on_status(self, msg): + self.graph.update(msg) + foreach(self.status_callbacks, lambda callback: callback(self.graph)) + + def subscribe_struct(self): + return self.node.create_subscription( + DiagGraphStruct, "/diagnostics_graph/struct", self.on_struct, durable_qos(1) + ) + + def subscribe_status(self): + return self.node.create_subscription( + DiagGraphStatus, "/diagnostics_graph/status", self.on_status, default_qos(1) + ) + + def shutdown(self): + self.node.destroy_subscription(self.sub_struct) + self.node.destroy_subscription(self.sub_status) diff --git a/tools/rqt_diagnostic_graph_monitor/python/utils.py b/tools/rqt_diagnostic_graph_monitor/python/utils.py new file mode 100644 index 0000000000000..6e66102b16dc9 --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/python/utils.py @@ -0,0 +1,29 @@ +# Copyright 2024 The Autoware Contributors +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from rclpy.qos import QoSDurabilityPolicy +from rclpy.qos import QoSProfile + + +def default_qos(depth): + return QoSProfile(depth=depth) + + +def durable_qos(depth): + return QoSProfile(depth=depth, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL) + + +def foreach(iterable, function): + for item in iterable: + function(item) diff --git a/tools/rqt_diagnostic_graph_monitor/python/widget.py b/tools/rqt_diagnostic_graph_monitor/python/widget.py new file mode 100644 index 0000000000000..e7f022e5907c0 --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/python/widget.py @@ -0,0 +1,85 @@ +# Copyright 2023 The Autoware Contributors +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from python_qt_binding import QtCore +from python_qt_binding import QtWidgets + +from .graph import Graph +from .items import MonitorItem +from .utils import foreach + + +class MonitorWidget(QtWidgets.QSplitter): + def __init__(self): + super().__init__() + self.graph = None + self.items = [] + self.root_widget = QtWidgets.QTreeWidget() + self.tree_widget = QtWidgets.QTreeWidget() + self.root_widget.setHeaderLabels(["Top-level"]) + self.tree_widget.setHeaderLabels(["Subtrees"]) + self.addWidget(self.root_widget) + self.addWidget(self.tree_widget) + + self._timer = QtCore.QTimer() + self._timer.timeout.connect(self.on_timer) + self._timer.start(500) + + def shutdown(self): + self.clear_graph() + + def on_timer(self): + foreach(self.items, lambda item: item.update()) + + def on_graph(self, graph: Graph): + self.clear_graph() + self.build_graph(graph) + + def clear_graph(self): + self.graph = None + self.items = [] + self.root_widget.clear() + self.tree_widget.clear() + + def build_graph(self, graph: Graph): + self.graph = graph + root_units = filter(self.is_root_unit, self.graph.units) + tree_units = filter(self.is_tree_unit, self.graph.units) + root_items = [MonitorItem(None, unit) for unit in root_units] + tree_items = [MonitorItem(None, unit) for unit in tree_units] + link_items = [MonitorItem(link, link.child) for link in self.graph.links] + self.items = root_items + tree_items + link_items + + # Note: overwrite link items with root/tree items if there is more than one. + parents = {} + for items in [link_items, tree_items, root_items]: + parents.update({item.unit: item.item for item in items}) + + # Connect tree widget items. + root_widget_item = self.root_widget.invisibleRootItem() + tree_widget_item = self.tree_widget.invisibleRootItem() + for item in root_items: + root_widget_item.addChild(item.item) + for item in tree_items: + tree_widget_item.addChild(item.item) + for item in link_items: + parents[item.link.parent].addChild(item.item) + + @staticmethod + def is_root_unit(unit): + return len(unit.parents) == 0 + + @staticmethod + def is_tree_unit(unit): + return len(unit.parents) >= 2 and len(unit.children) != 0 diff --git a/tools/rqt_diagnostic_graph_monitor/script/cui_diagnostic_graph_monitor b/tools/rqt_diagnostic_graph_monitor/script/cui_diagnostic_graph_monitor new file mode 100755 index 0000000000000..8b0685125d026 --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/script/cui_diagnostic_graph_monitor @@ -0,0 +1,14 @@ +#!/usr/bin/env python3 + +import rclpy +from rqt_diagnostic_graph_monitor.module import MonitorModule + +if __name__ == "__main__": + try: + rclpy.init() + node = rclpy.create_node("test_rqt_diagnostic_graph_monitor") + test = MonitorModule(node) + rclpy.spin(node) + rclpy.shutdown() + except KeyboardInterrupt: + print("KeyboardInterrupt") diff --git a/tools/rqt_diagnostic_graph_monitor/script/rqt_diagnostic_graph_monitor b/tools/rqt_diagnostic_graph_monitor/script/rqt_diagnostic_graph_monitor new file mode 100755 index 0000000000000..a5237a87e87d6 --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/script/rqt_diagnostic_graph_monitor @@ -0,0 +1,8 @@ +#!/usr/bin/env python3 + +import sys + +import rqt_gui.main + +rqt_main = rqt_gui.main.Main() +sys.exit(rqt_main.main(sys.argv, standalone="rqt_diagnostic_graph_monitor.MonitorPlugin"))