From 4917b54caa1331f016eec6c65f396765120c7f89 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Mon, 22 Apr 2024 13:34:53 +0900 Subject: [PATCH] feat: remake diagnostic graph packages (#6715) Signed-off-by: Takagi, Isamu --- .../CMakeLists.txt | 19 +- system/diagnostic_graph_aggregator/README.md | 41 +- .../config/default.param.yaml | 1 - .../doc/format/edit/remove.md | 4 +- .../doc/format/graph.md | 2 +- .../doc/format/node/remap.md | 21 - .../doc/format/{node.md => unit.md} | 18 +- .../doc/format/{node => unit}/and.md | 4 +- .../doc/format/{node => unit}/const.md | 2 +- .../doc/format/{node => unit}/diag.md | 2 +- .../doc/format/{node => unit}/link.md | 4 +- .../doc/format/{node => unit}/or.md | 4 +- .../doc/format/unit/remap.md | 21 + .../doc/message.drawio.svg | 677 ------------------ .../doc/tool/converter.md | 29 - .../doc/tool/dump.md | 36 - .../doc/tool/images/rqt_robot_monitor.png | Bin 87323 -> 0 bytes .../doc/tool/tree.md | 26 +- .../example/dummy-diags.py | 6 +- .../example/example-edit.launch.xml | 6 +- .../example/example-main.launch.xml | 4 - .../example/graph/main.yaml | 2 +- .../example/graph/module1.yaml | 11 +- .../example/graph/module2.yaml | 8 +- .../launch/converter.launch.xml | 6 - .../script/dump.py | 94 --- .../src/common/graph/config.cpp | 454 ++++++------ .../src/common/graph/config.hpp | 129 ++-- .../src/common/graph/data.cpp | 97 +++ .../src/common/graph/data.hpp | 56 ++ .../src/common/graph/debug.cpp | 75 -- .../src/common/graph/debug.hpp | 29 - .../src/common/graph/error.cpp | 58 ++ .../src/common/graph/error.hpp | 92 ++- .../src/common/graph/graph.cpp | 221 +----- .../src/common/graph/graph.hpp | 31 +- .../src/common/graph/loader.cpp | 189 +++++ .../src/common/graph/loader.hpp | 67 ++ .../src/common/graph/names.hpp | 42 ++ .../src/common/graph/types.hpp | 31 +- .../src/common/graph/units.cpp | 224 +++--- .../src/common/graph/units.hpp | 220 ++++-- .../src/node/aggregator.cpp | 58 +- .../src/node/aggregator.hpp | 16 +- .../{plugin/modes.cpp => availability.cpp} | 32 +- .../{plugin/modes.hpp => availability.hpp} | 12 +- .../src/node/converter.cpp | 133 ---- .../src/tool/plantuml.cpp | 20 +- .../src/tool/tree.cpp | 42 +- .../src/tool/utils/loader.cpp | 57 -- .../src/tool/utils/loader.hpp | 48 -- .../test/files/test1/field-not-found.yaml | 2 +- .../test/files/test1/graph-circulation.yaml | 2 +- .../test/files/test1/invalid-dict-type.yaml | 2 +- .../test/files/test1/invalid-list-type.yaml | 2 +- .../test/files/test1/path-conflict.yaml | 2 +- .../test/files/test1/path-not-found.yaml | 2 +- ...-node-type.yaml => unknown-unit-type.yaml} | 2 +- .../test/files/test2/and.yaml | 8 +- .../test/files/test2/or.yaml | 8 +- .../test/files/test2/warn-to-error.yaml | 11 +- .../test/files/test2/warn-to-ok.yaml | 11 +- .../test/src/test1.cpp | 20 +- .../test/src/test2.cpp | 23 +- system/diagnostic_graph_utils/CMakeLists.txt | 20 + system/diagnostic_graph_utils/README.md | 13 + .../doc/node/converter.md | 31 + .../diagnostic_graph_utils/doc/node/dump.md | 46 ++ .../doc/node}/images/rqt_runtime_monitor.png | Bin .../include/diagnostic_graph_utils/graph.hpp | 133 ++++ .../diagnostic_graph_utils/subscription.hpp | 53 ++ system/diagnostic_graph_utils/package.xml | 23 + .../diagnostic_graph_utils/src/lib/graph.cpp | 109 +++ .../src/lib/subscription.cpp | 67 ++ .../src/node/converter.cpp | 53 ++ .../src/node/converter.hpp | 32 +- .../diagnostic_graph_utils/src/node/dump.cpp | 145 ++++ .../diagnostic_graph_utils/src/node/dump.hpp | 52 ++ system/hazard_status_converter/package.xml | 1 + .../hazard_status_converter/src/converter.cpp | 230 ++---- .../hazard_status_converter/src/converter.hpp | 26 +- .../system_diagnostic_monitor/CMakeLists.txt | 13 + system/system_diagnostic_monitor/README.md | 16 + .../config/autoware-main.yaml | 70 ++ .../config/autoware-psim.yaml | 11 + .../config/control.yaml | 73 ++ .../config/hardware.yaml | 121 ++++ .../config/localization.yaml | 43 ++ .../system_diagnostic_monitor/config/map.yaml | 16 + .../config/perception.yaml | 16 + .../config/planning.yaml | 90 +++ .../config/system.yaml | 27 + .../config/vehicle.yaml | 16 + .../system_diagnostic_monitor.launch.xml | 7 + system/system_diagnostic_monitor/package.xml | 25 + .../script/component_state_diagnostics.py | 102 +++ .../CMakeLists.txt | 9 + tools/rqt_diagnostic_graph_monitor/README.md | 1 + .../rqt_diagnostic_graph_monitor/package.xml | 24 + tools/rqt_diagnostic_graph_monitor/plugin.xml | 16 + .../python/__init__.py | 37 + .../python/graph.py | 127 ++++ .../python/items.py | 54 ++ .../python/module.py | 61 ++ .../python/utils.py | 29 + .../python/widget.py | 85 +++ .../script/cui_diagnostic_graph_monitor | 14 + .../script/rqt_diagnostic_graph_monitor | 8 + 108 files changed, 3429 insertions(+), 2292 deletions(-) delete mode 100644 system/diagnostic_graph_aggregator/doc/format/node/remap.md rename system/diagnostic_graph_aggregator/doc/format/{node.md => unit.md} (59%) rename system/diagnostic_graph_aggregator/doc/format/{node => unit}/and.md (71%) rename system/diagnostic_graph_aggregator/doc/format/{node => unit}/const.md (86%) rename system/diagnostic_graph_aggregator/doc/format/{node => unit}/diag.md (84%) rename system/diagnostic_graph_aggregator/doc/format/{node => unit}/link.md (67%) rename system/diagnostic_graph_aggregator/doc/format/{node => unit}/or.md (66%) create mode 100644 system/diagnostic_graph_aggregator/doc/format/unit/remap.md delete mode 100644 system/diagnostic_graph_aggregator/doc/message.drawio.svg delete mode 100644 system/diagnostic_graph_aggregator/doc/tool/converter.md delete mode 100644 system/diagnostic_graph_aggregator/doc/tool/dump.md delete mode 100644 system/diagnostic_graph_aggregator/doc/tool/images/rqt_robot_monitor.png delete mode 100644 system/diagnostic_graph_aggregator/launch/converter.launch.xml delete mode 100755 system/diagnostic_graph_aggregator/script/dump.py create mode 100644 system/diagnostic_graph_aggregator/src/common/graph/data.cpp create mode 100644 system/diagnostic_graph_aggregator/src/common/graph/data.hpp delete mode 100644 system/diagnostic_graph_aggregator/src/common/graph/debug.cpp delete mode 100644 system/diagnostic_graph_aggregator/src/common/graph/debug.hpp create mode 100644 system/diagnostic_graph_aggregator/src/common/graph/error.cpp create mode 100644 system/diagnostic_graph_aggregator/src/common/graph/loader.cpp create mode 100644 system/diagnostic_graph_aggregator/src/common/graph/loader.hpp create mode 100644 system/diagnostic_graph_aggregator/src/common/graph/names.hpp rename system/diagnostic_graph_aggregator/src/node/{plugin/modes.cpp => availability.cpp} (66%) rename system/diagnostic_graph_aggregator/src/node/{plugin/modes.hpp => availability.hpp} (85%) delete mode 100644 system/diagnostic_graph_aggregator/src/node/converter.cpp delete mode 100644 system/diagnostic_graph_aggregator/src/tool/utils/loader.cpp delete mode 100644 system/diagnostic_graph_aggregator/src/tool/utils/loader.hpp rename system/diagnostic_graph_aggregator/test/files/test1/{unknown-node-type.yaml => unknown-unit-type.yaml} (74%) create mode 100644 system/diagnostic_graph_utils/CMakeLists.txt create mode 100644 system/diagnostic_graph_utils/README.md create mode 100644 system/diagnostic_graph_utils/doc/node/converter.md create mode 100644 system/diagnostic_graph_utils/doc/node/dump.md rename system/{diagnostic_graph_aggregator/doc/tool => diagnostic_graph_utils/doc/node}/images/rqt_runtime_monitor.png (100%) create mode 100644 system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp create mode 100644 system/diagnostic_graph_utils/include/diagnostic_graph_utils/subscription.hpp create mode 100644 system/diagnostic_graph_utils/package.xml create mode 100644 system/diagnostic_graph_utils/src/lib/graph.cpp create mode 100644 system/diagnostic_graph_utils/src/lib/subscription.cpp create mode 100644 system/diagnostic_graph_utils/src/node/converter.cpp rename system/{diagnostic_graph_aggregator => diagnostic_graph_utils}/src/node/converter.hpp (56%) create mode 100644 system/diagnostic_graph_utils/src/node/dump.cpp create mode 100644 system/diagnostic_graph_utils/src/node/dump.hpp create mode 100644 system/system_diagnostic_monitor/CMakeLists.txt create mode 100644 system/system_diagnostic_monitor/README.md create mode 100644 system/system_diagnostic_monitor/config/autoware-main.yaml create mode 100644 system/system_diagnostic_monitor/config/autoware-psim.yaml create mode 100644 system/system_diagnostic_monitor/config/control.yaml create mode 100644 system/system_diagnostic_monitor/config/hardware.yaml create mode 100644 system/system_diagnostic_monitor/config/localization.yaml create mode 100644 system/system_diagnostic_monitor/config/map.yaml create mode 100644 system/system_diagnostic_monitor/config/perception.yaml create mode 100644 system/system_diagnostic_monitor/config/planning.yaml create mode 100644 system/system_diagnostic_monitor/config/system.yaml create mode 100644 system/system_diagnostic_monitor/config/vehicle.yaml create mode 100644 system/system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml create mode 100644 system/system_diagnostic_monitor/package.xml create mode 100755 system/system_diagnostic_monitor/script/component_state_diagnostics.py create mode 100644 tools/rqt_diagnostic_graph_monitor/CMakeLists.txt create mode 100644 tools/rqt_diagnostic_graph_monitor/README.md create mode 100644 tools/rqt_diagnostic_graph_monitor/package.xml create mode 100644 tools/rqt_diagnostic_graph_monitor/plugin.xml create mode 100644 tools/rqt_diagnostic_graph_monitor/python/__init__.py create mode 100644 tools/rqt_diagnostic_graph_monitor/python/graph.py create mode 100644 tools/rqt_diagnostic_graph_monitor/python/items.py create mode 100644 tools/rqt_diagnostic_graph_monitor/python/module.py create mode 100644 tools/rqt_diagnostic_graph_monitor/python/utils.py create mode 100644 tools/rqt_diagnostic_graph_monitor/python/widget.py create mode 100755 tools/rqt_diagnostic_graph_monitor/script/cui_diagnostic_graph_monitor create mode 100755 tools/rqt_diagnostic_graph_monitor/script/rqt_diagnostic_graph_monitor 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 e4aa169f02addf3c6a60972c41bb4aee228e06b8..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 87323 zcma%iWk6h8&n{BjiaWGGp}4!XxKp6G>l7c{wP>;84lPb`_rcv-26uNG+_}^DJ)G~# zpPN6!Y}V|ZtYjs5lI-wLO41mpB&aYjFc`8j5~?sTuU27T;F*yTp;vgUFcY93ubjkW zKO;lQ8`&%j`kmNWQp;J*-on|<*wGvYU}tY@&g^9BXl`!j^u^x!1ioDax`@;AvzD{C zqq(uOrM=yo&z834(2FoI9Bdq1TTQiWoZA^;>|EQ)`ES@cwo?N+__o4AxOsO9IUxsQT*jH!fI7Y(`WQ=_-FzhMZkf z!p^{NvlJc|lD{r6C-P7yyfC=)0B(R~QL#5c&N$zevk%g&c?D|#z5qHD$khlxqS1yB zb$WlR$oL`q#`y?{0Q(=Jm(k!c)SVOBzVxt&;TsdNKp&_^UFEnJs4&)Z9ha2&hfsAa z0(9?onlR=kKs=3nlf&+y+L2*Lv)NR&A4y9|a}H+bDG-l7ftU3XXAC7qOsu)f)u<~R z$HRwYQq4Ob_K_PO5bc_lIIPnZvf?9V{=Iv3{0t0B;Sc5p-Me~lC{XH7_mdMYXwLCQ z=WRyVKcq(=Obkj*_0H5MCtM6nn|rX=4z@`Z9#?!XO*;-2weV)4`iC5g&jeOG}p)$CXco<5ehVOc#zyt zB85#>ze!SGO@dha{Xl*V*9b$|p|lN4Mr;5dZ2R&gRX&dBz+t;J1lI59c`)o9^lt*r zwKeY8SWHPRKQ2nX)zg60)A*^|cgl?X9-Jo|Z_yos(bDFy(TD%|@Sx|~vSdLtH2Jb+ zoAbun1O^o|3Q*DpdEb`L82UZ>4JWf2A|Ar8^NFIe*vg|VOoZAK2Ad!jQ%^gR93?r_ zz?&b;RIGTe_k=4azE{a9S~%+4fEcCG7Fe2SYe(JSzUaB>jwmEx)S}y>W(~*(6v!mw zcieQoK3-aRJ|7p|i6`mtkj0pV$b1;P0~3>_d_n2OPB&Ku*wB@-MSN-*@gMSyfDflm4K}FqnbvL1uzBdYc6Z!IZG8Hd8<#jYI z*{yGE$jZre{YUXh=K7V@0695SyM}u`n0$dVgV33SeCNFhNm_*zw(N6QJrc%lYDYxAMqOqT44^DjRaO0>rgXWvyF&!7W#(&J z*jNg_y;lLUco|0_;Qg~XvEC6eG5s5m&HG1+n9!RW_o>)^0kUG;{(P)e4z%?*`Y_2; zyA8EF(a!cb*x0dtf{a<>eq}~aCpB7rdL_Bf8@qSk!ou`87wz0YQl91sJXmS_18U@Z zoHdc!^ODr7Zw^+E^c(@&cN_8&5}Q`$`59{iS#4y>AO*S$n{7Ypm9_W^U(+Lp^SHF; z!#cxXJ&F&f>yHa{L)GqLq&mIhZ_ zpZn)Z4+9?}N4_?qsWy*@HC}Y@K#hBo!K|0rY_prPW=JhugfcqMtJr!c`^dV=^}L5* z`bbDTuqnJw5ciAU63H@1=gx@Se7XPRbolOzQZMcIK=}3_CK8{UvuGQf^G&;vy;%YL z{CX>m2=)`#@l)<(Di^L8thkWR_>=X4e>q63oOr`?oYst4yI7Mb?5~3 zMiADR^rB{YY!lnmqdh;4n3EIR3)jKY5?9xk!Zj*@1)z#+BJp4!wRXw7tJ7>Ln;aFo z08$MrCGHdyd?d;$DZAybO7_ejwG48fFk0WwQA@`%O=uZ>9DOp))U1WLSc*>qS z6d{d|?^iO?F=}eyynLPp4&!2=u)#1XG2bR?BeiM~We9nqV<8ZB=ugeCtvsRlyvB}g zZBEeTu8E6_3(U?o449799zdK6bwbb%9ks}X`qfBEQHq#;aj26Bm^`(8xPe?8FWu*y zGGn=zjZCnhuJDm|m|umA1oA;epl8}PPV&8`=A5xLJ^7|V0N49Wz(MKLHU~i#Tsm5kRjY-Hgl19_vS6%B@kdMx%p+whcz54i> z`8KaqZcnnBhU1;xK~5S^pZ6NY*tR5u#^V!`r7NWHo%zK}$G&%$MY1wFy8KfcOT!~7 zD{O%Kx6%DQIN3I@KT*Z?=^t+_r!%bE!(^3>5Q)YH%f4f?;@tvG%w2R2t$EMs!%JI` zk24D<-g^(|Hb}1W*JZAV5_jIXRM}+QBZb-@E76yS99TQ<_t2}_-&FFo+2EX?eECoq zhvNp!*pjlEySZM zj69W`*cq^IU(K6@FLPvP*ZUh^zZ+OlS{z(@fPlUDL) zi;e8LcS!BJboOM;cb#z7PaHq}YMfCry%ND~Klo;pB@leCfL=w5*YMa~v6grv4D~BB zwTIi>Eg7~3j4o#AYsYQZ%Mo_6qtfL3=9a0^{=>(k(4<3kHWJ6#`xf`O!m4|Ny(&9x zbcYjjl{P3OrgiW~dN+IWQ>fR<{nv;myvoG<;o;kqd-`}MU-oktyIi8tY|r>Yogm=F zb!;o2EAs-KvYAUi;7eN4@7b zyh7h*0}c14ye~EdnZ7xEDtrdCF46|i*$WNs9GJ{C+953$xKw5jG-WwGa>)H&%U5m` zJ$u!T<(F1Ps#Iy!>v}g`E}Qf+aJmDP#M`yc8_y*=>T=WcW+7%ar9 zdG0V)qIIvddH3aZQwGtEDcGY<&yX{k6GA|w1Sj86U<#&s-SVw?<$2&DYLG8?{!h6p zvM=IyJn4)b9Z-m!hR+I|#a=-@WFwHqm&2BgTdQv z8A~g$9X2WPgLlp)YfH$UUib<;6_ul6<-(CRi_rJ%DQWOL(}2KP$&UjWN>G0GIrEY0 zWa)Omuq1iY5SU{OHu-6km=x-?V~0m54AOw4hu`J~zKuFemg0xaY&5MBb@x;H6~c!1 z&o+p{mN>t0Z!>DxIiLhe-@a$yC#+r@(b;}<$Vg)r<7)FyCMe%{~(Eds-cyYJ7Xiz4#C03iI%6LFi#H?!Ga>#SR$VfXA?tU zfyc}IjA^O%mw;mI@#0xCg@@whGPF9M4&YV}`QKfs^xcxw$bR+`M%(fBFrjW;5_V1z z4hp}=Vn4W_tMw`yRd?{Aj>na`(D6s3EQFO}*IAxUt?R=KOn3XyjD|iOIw|UbD=SmW zM)edmb2{|*#Ku~G?OyA!YapCu$a8HGHl!Y}E}<6vX!LQ$xMq%s4`@^Xs~bVU+_)A( z%CVH(FHoH}&0H7aEXV<(uR;8qW;sIrjooU*qL28yZ+Grt%Fds1%m#uPNl9k@G(X2X zmuQ9%DEtZP;a*isM;F}5)jB2v|}{hF-! zc)R{_Hr|9U@k^mh)19;Dg$tq^OFRkcWD5+sG!vnL%yS(q9`&WhWMn$$lE(FHm8q$tlg8hKMQ_lugi@n1 z-tE~5X{&bj=RkY3FIHHXj3)#F$;->rQzd0dj_~(~`I|s@b#)=aSj&tP+YN>_XN%+*P~|$Hp|QQ5IzCe~z`E&5K2d)KvUGzylhI+4kue_&wkVn(lW;_U(d&> z*qUcmulI5LG;+M=Zs8~Y1QsQPvOlQt>C-2WlrMfy7$@`=^#_Teu>yY9ce=`)EeI~o zzT^J__~7v)*Z7o_l#MQQ*A{Y7QPB*g!u`gezcNw0JJCZg zOf$D$OfYKs#|+agm@*G{ZCqyD-$kue{0~P>eKvE|!96_^4C=pvMw41d=@r3dC(CU% z3-wV&MMaY{Oc4%h(~yl3j0-!%WIC^g9~z(eU`Xr9EtcxVFUUp0MaZq33=8LH(Q|*_ zIltQ!@R#R2Ja2jsG8He6KAHj%V6BiO?&SQV0g26_h^VN1)qFW~5p&!l*=>4yCm67xS`7mz<5Y{2sUmCiCL>e`0W`gnuK_b! z%v}}}T=3di!e$T`yEso2x6BmaScMlubYjtC5xfx z;S&go)8SSXTRtowdHVtIySlqkuqr;xk&HGzHnES);m0I)->ND-jV?0N$qqW@8(gv8 zB^l0Sjck%pO#4m*eTxdMS~Y8K+cqu`QBP)Y^Bs4!&r(i_9t=P@Vc!*XnzM(q;41Nb ziWS97Po5}xkssfbBDGh(%u2Op`*N~qA#&`|V55Y8fj?eyu?lLSzG-!_#xaW{9oGe? z{UL11)K_B$|@VG9DO z*gk1$ZJzi!zorXDyH7X)$|ljb>aJ(_9dr63vpzmWg!loY?ZTG~p-#GwKF|xm+oscV zNbhmFfO1BEx=1hTS~;s`mDe~e&lu@={MOTIae!zg|1FN^cXGyXp9m>V7cZM6N>!5! zJd08h2fKC;AhFsu8NGk}Lipi1HRH1vrTU@2N054U3}B;JzDe)J0cfTuGa5YFzAGVk zpgg%Q8|!4HFc}E4rLn;AP|$Bp6d^yTGCQ(MvY$ojI2JG5y&7@9YdsUCAm=CcPr77y zO}5#e)Yh-v{)mj_YTYy0tIG=>C<${+GxKPjy-95@d9xE;ZWQZb|@_Y%TIGXx;Z%EYL>La@&UNd_% za&sX`vHRz1Xh@{-RXHCMV~A+GPv)PR=*p*1USh6YeBXsw2buJEEAB2WAs>W4wEoFH z@`a9-Ch!xioUxYoFdFD3eV~z959^f6TSg)8dvc+>rMMnQ{I~U%bp|jgc};M{gk8* zvssJ>gf0%oR*6jw3KSQ<0&r~sYzWvEgSMe+N zBcw3yU~V|iJ2Yk7+~nC^mLzWPEss_*MX=JAb&k&ug z1h3mHxUHYL_6l`v;|mrow({g3?HODbD=cjXls-6-7M}AXvy7MgfD>A>Mn*(zxqj|i z2~|?7=bB{FO%Pb4Aer*TVRUgP%8tH&BMw72UK;DO$3Ok%_|*04rq=v4)J>Jy1HZz@ zHK9e+FCqH!k-ey|Lz>`^$D$sEjSCXu>VgH#xQIKhxvf#+-f&!np~+Ly(`QavPR}i7 z^vsp7w36sW*kfuX^QTW2OU{ReF$~5cHqoW>;DRj!NmczrB_AMVp4QcX@q zep`7F-Fxjn<+WFT@ta?9_NIZWRNDwQMn6_ZqZ|C~$rocU7#6y|qin(|m54YMeu|Rk zd{n?yX4n5syMvDZV$NVk#eirwQvh_^B==&`!Q;SN+|BHf*c&sZhXEUMx%APFJ>aTi zft?5o9jovxPIC8H19+y!e1-nuQE%3U=fPW#h$yu_o>7D2&%*Pzk++qO#jC`hQd=f` zPTq!aRsBCDWIlvAEuf$?qv)Ed+1HFp8{eX?NTp#y_e{DFUO*BwHm5S~ z7ReF*1jj;D0(cdqI>{Q6TWG?c*_s}oZ-qnQU4JcwO~nx6@a05hz0`!?tq*zijwdtx z$>?p3(u2~M9XI-uStr***^#xwd1Z3iJ?Db59IO5{$GD7D+CoyP(GC9VIbws113iAX zkN>0#n{rig>wJl?2V6P{L+znCj_F1;^<;_8w|vs8{OCX@0c4aj^YJyJD{|rPoJ*wB zbC)&XY}Eor&JclVe?YuM;;>|SyyZuL*7=DQaA7>ykGYXQj zg`RvzcWV57RcP?*@8h4@3}F{1qY@qNnt->Bz`Mpu!TL|!-UJ#GzBVD9BbnSXatg3K z03uibUF~P{Uz1j1?H|$h?xwYpYCRK^KF+Abb!YHxyyLdy3>PHEFt^6ZkPV(r-5`@? zl5_v_0S>ndC_za_I|t_nUn*gul<}rg3;78knvfxdboaR}mW5r|R%r*l-J%|N$bRCp^%*X;rZ&Ifjq}Hcc^sM`*mnHv^UXF zId`*B0ne9-dFU$0k_=zi9k67Vt6}EAb0i?P#PIH1Gp-Dox0Njd175A2%lq5wjCAyV zjf{izDUqt~!Eg_kV%80J(43&v z>3#ivV;k*qO-+LbXD0lZ)L?zgsada~`$;G_4W6~cPI=YC^}VHyVB&|x&MoMl2$L=6 zQVdybJJW6U!qyFxbjKraHJ%>G!Hm}hw(68{R&_gB>$ta1Gf`yFR)*&zYvgk~>P1r% zqKFjC&t6*zN`56VRWgUcRB4A0#yE|Jsji(qB`)UFCu;U;dr_?Hlr>U?s#P_z@aVVn zEYS&i7uqkDv>&f9682MPB+%dM*5`X-lC}$eRyU?} z%PbWUp@f!&nf1$Yz`4~k&twS+)BwBfM6-YKjgO&e)*ZTB*l35(w5N!lxN_4|Qh46p zIVU;jJ0beqvM63fu7i^5il(lx`!bsn$E7cG?TkQx{BD>onKpdx$8CiMe*b3iP!QK$ zezHNQb=vHa>*6tn_COubL?W9iswqFhrlPn>^kx2-piiSTB+1Y%8 zepp;g54HS*9~t2hk1RCr^?&2d8T3U%j*LAVGf>RiDb?MA_Tb8Cyel3U;tq#=<(7eQ z>bU#w@x!mSnqv5im5hnp+xSP_vxn>&OtlFF-Qb8#<6mY0j`NJWLsF6?S7zu`IGBQF zD4J3)1#`69snf*!H=w43tzJ)5$AF(};*LxWO6$*p@4xkyp|j~r9F=XAt)d};eRXF> z{tBO7byLNNc@=hXk4O2Ac?Nb7OVpd!6AJ2X8Tc4}p*Aef^BbPv{{t3d8BOo6j(U1~ zRm%1FZR!`JWH=P#g}ts`MGoCl5`O$Ix+=ZtS-!tzy9NS!t{(6>TRiMX+xm!UXPp-2S@D7 zm))jQ<~HF_Wlk4}#L!mr*fael?8W656+N(o z0ISZ{ehT?YZ@^if=)|7Pjl3X42^zrv4v}Nw{=ZOllL5lt_A*rbtzt+=$A@2^i{t(W zbxJ(ZJCb+w_V)hmgbHzkJTLc!2%!zO|I(Rq+yM;c8ycECqj5VASy|VwV8UeKqdFoD z?<)p1s;t$za{Ma5LdTX#Y@^>hc`T{lr4GaoQDOq}he}DMLgJqzniGKdWBe}?Y@Rje zICXf``}FH`Tb-^3>AR1&%Z(g2m4++9bwF#Mc@F2Z8=#CtkGb|;U0;1K95k4Cc(i5H z-+tTGD@>(MIy6TqeWyF1&6r&=!I!3Yn4X0uoBw&G(;SzQdc{z=h> zVjMF`DQc&lFuU*|pqOdF$)Rg|>0Hph{T%lodSpGGFncSQ-48ec$LT5v7WIw3Z@xC^ zAQi0^n8!#V(?5O7`dk}^FB)Uiu>^l>drhwq<&#=NC90 z3Fu!kpGfjBA~->(=%%DAo4n$A=vXD}ucBqSJm4&8HyLPg;w$>-{Gxl!U`B$DrUq8? z{o;DAV%=m5TUSooIXez1VEym+^IXNRo~D{0^;wJ4Ib=`A!Vh8#hgTm|FFa|51pTqx)N`-FSm2_dWVHoaj*BX6Cakt_->=6xJ*}PIY$xw&2^@5H zYWRLK=u>zl8oMPMJ#{psc+ATF-?@HGEM8ldC25W<3X8JD`tyz5pE=Jm&eC+ABwORH z_r@0bx(x6u)#j&}f=P3Jh07-L6DuRcEeSt3@*QZ&Odz$k8D}us7f$xEY~GrYrprn0 zOpAwFcjThcl>J?0gC95+2>tp|HQB#ezRr9}D%96dd%5gfnKFkUuDqX?Si=s|8;tuW z%@5D?+!L^M!V&9+)=t#Y(xTEQHt&#ctZ_{1oi}3d({Qy5$m#^HHr9{Z z*MLqlGzBd4VmRL~u1yL^mcFQgvoEX#Y0RfIoFz$?%}hJz^&8vnwHj!kH7}`3_ai%@ ztTr3H42ATKjM|5`w(P+6dkk!pR7*%{)PyA(TcXGW{4C0w^HD!;`OmpFBaRM7cPu?SSdy9s@Gm7vuYq6t;{p9?T<12}x z9B|fFRe(M9kQmQ)HY>Wqdyul_gz9kB+d|59tsj-g#KO!_cYguCXs(`g`EA7PLf zdNH59SMoln=@6g_qfXke-9vaV2d4jS?x46kGu6GXJY925V3>4bFB|g<7H>kV>_v{yaobXup&)DK$g)V>*u-#^u#jiwRXDEi50s0Z=<&@cSyUGEK_?>d&_xr0Ox;FTGu zu1C9H_46UMb7~!kyNqHhMEZU7`0M6Fvo5gafG$NcZNhuTCTZl{R5~K-bMgMq+v9Al zX10{N%XE&~uyx*-U{%tK--y5+Y#UJstTm+*;3`r)ny)L?FGL|1th2b^%s)IOnmt^F zxI=V|Ug75ldZgsi#mj`r_cUmDc?$Zirav$AgqyJ*bKYyUK;F=MFn7zXIy=KjMiBPS zc!jhL?^Kyx&mrJO!iYsIgo!w21m*Fq$8kzHNWFHk-|y+nURjUdtJ|F{<>EnybJR_@ zcdbCFHw-C`b#XC=wsQy3Y7V&soMxe0SZNk28jE4SI*D|0z953@6`a1i zVoLaxBuK61q~Z`#q5Q0Dn17f7%T@L%#1Z3o3*6MgmpG#?YMb8(`3a(FpULy>R&*{Eb9X$y9< z9r-%}-a=K{jn_4{!y0JEBC!!}Gw? zLUV_4YaWgF9lj(3c6LGmmLRXP%2U-CW_^B%!x9`n_wHV1tt3$YzcYy-*LZiz?G?fEKV58TCW{yJA3etScDJa;cd+$s9Tl*3q<+YHN9) z%%Y!m;Iv8aFAt63dLkjldZ*$qU6NqBmQ!Y1PIPKzTLypJCdBtI4T2_DXl4HY_`dZ& zrF!gJ-V`AZ4j5=&*1TEI1*f!0@&o&&S&=-xIT$~V0ECW^IU)mwR~8f&Wo2n-X$uzO zWFQ71{vBuEGZH*OW)0eGihajMYlqxqvh?4#B~Z2Z#|>5G`c9rp4gPj|pcK0(M+t&e zNaYBoS1Zs{O}{0D-B}uHq~JZ{(hJS3VFy$6I$EVYwvCHhKENnRKi5%ZG5Xer=lM%6Zj_kawlP z)2+<2_knQlh^S%)i+IEBpgFg3*DK$rTL3g8>?Lwpr$HhYT3B3EV7%hDRdZH@~qlPk&; z{yNOMAs?0#?X<2-I=lRN=Um6Sey|e#$9FT-nXx{ec*T2A*{Q*}!V}HyvL!~B0l`Fz zz4XD6=77=p=WH|O%}K!>`r|sRRpUfmXZS7Iswb>MIm}7(04`B}DEo+L=Vi z6pqrpfGbN!#p_;Sk{eQxt=g!@VeZ27rRzU64zK#EFh){^5LAML+`K>8}Z&g3I?E?~MtMEW|uB?2FA=|zPf`4_S& zI&sIH3(s6yZf}bhh$-2FG()aC7cUGAPHxE@a77Ee=J1s4ZWBAZXC~Zw&e2<&sPf5+ zseM_B0?vzb{Voe?T}6k|j>2oP_=kc5uGx<6c-nro+q015LB3H-5mT~GSbRtPHFG$pBGo;xQMGn?9$ z^hCP5suh%2ypoX&qSl^xm-Cc6L})SmQn28jW8S(nKzjXS!o03HrPP(zPs|0wc@?h| zDTYktNg-SJkH{j`-_)z@I%r&n$p~ma=MUp%?)jJr*b6}ru{ryJx;?Vn?cnSRxX`oC z#`j7}K8Z*L>RX~dB{=S8wBq;PQUmAW9y=euDz3DTn3{^;?){m+q5t~df^w{1st^K@ zB8KiVeCF$noH6*skkhk_6=qDwhnQGB@<7Nyp@gPE_?il*|UWh-zPw~#p#?byZW%_{k*HJ+3rKTdyxhC zEMGRg6z_8RaaRlYl|ril)^Yss&Dw_WBL5wyoi$n5M~q**L3!Mi7W2mw!ou%$I}KjX zh&{c_$<2j$wq5N0*~sxRs7MwM#Z+l^hd5Qt+3*NaD2HT=0w=%7Cf`=DpPUGu&Itqy zH;5=uZn(9E8?@3RrSKkmbx~&Yl+8#RQ3sYU4S~Im5h>c2qZbrtc|;J}PY;@!+!Q;8 zMPiWby_ry?u=lx+m1z9?<$+*2_gs4S^_)3n1ggh&^Q9{-0sV&fDK+Ik&I+7E!A7{+sK!TjjKNG5yZ3cXR5czHkGK*C_>hIn;x$gSliwL-s!kvY^L7UKn(pN zm6SDm-PY!OEV%A@Bskal1@b5XgzP^EkNtUsI6PnHN(qf%3kEBHrgYmB5A(pPadDNs)F1*+OKU)b#^FbBXNmjMR(&d5V}`tE^y61ZD~ptnbm zoWbR?Nx{uXr-l*zn=jhXY&(Sdj;JtRfeBjdePt4z{kPcbn^%{7D{+=2xsSa!FWTk` zTLVAOo>PqlJ81lh$2-0kj0p7U(-n``aY}!bB&e_s<6p|QJJIYk*LEMz0?RQ+<3NXn z`x~oD&vC~Qf-IKG3GBXiC0sqaK*qB(t49TKr}y}!G(2JrsWWLXXH39u2KRj&|>7K8v{D882gHj+B&jSzetYDeTvUiuPfccYHu<_w{4EUp^Yg zdMC2pKZt>1&bU&V+Nr_Bl#9%5_oXM5wf}TPj8~G>bz|cvd03@387qO**2nBBBbgfX zk9W5Vga71Q<%r?o;Y_;qhk-K_0AX$6@d$aMi1l|oo}ymYG#TXd7OTiCvh>dx%YfIP zN`$ZR{31{Mj%2ou6WJP`yKbIKK4jZlt%{qljAi!hnTGOj%50u)r+P#BPA2`1rPD&@ zfzwvX_B&wjb3bO{i86-HL8M#jicAu2`L(mMu_%2X_x;RgBLp{dg@l6~D0Ifyn_a`R z_dX|OMp}{c*m%RJ*{4#Y&2zMUTZ2nabQMOryEqY=SHN7n%XV|W812Y)G8cK>ejELc z`|c0ZVrMaVI=_B3OQI0tjrq?^i=%y2hF=tQLv*Lohs5=dBJn=>_CL+dw5_H}#CG$D z*4t1rqLqGp8O^!z9Iten5=uIB#YHrtu-NPA<)UCqCDaWu;w6Lj(4ORqC$=f5PHsc8 z=hgGvGEKDlpDer_-&rLqi&p=W%5DxZs^%d>adDf`(`AOn$2z8neEH<$z=3@zltIvR*Cgwo(CU|X7A3mGARuQc6eS;UNRU)5`Bmd5Ddc#%jwSTCRPy+ z#NnY+DQm{LyCUT?B$bu)vJxirZj>UjHGGHzpI~hr>nP(M>Be5gV3_Vk*;ZTfvS#PV zEbG-yLgrL{5D+A(1YS`S{^`RG8|45;QPin4pC5Rq-iUPDMXir*D1GBS9+kJ(_~~4k zJezp(=e*Y?qa!BG4b&-ECN7iO7V|9pC+(>Pw<@$@ZSJ|X^HO9+00zdrhsooeFw)kl{yE@tONB#6&PRNgwpBQP$aCas(LrbalhR%#YEbWU+=2!l@x{h zrQ)wd#=;Jr|7MxxR&&Ajmbyv}#TI5T#(9Vid%S?=QP{~$cGJFHsVEZsFQFYY^gI-B zfv3!;uZL;gu@E#crod?W_AP3;(*8Y49Ht{FQ$piRb}a^=b`L23Ls@w5}pWxG$j z?za^85wqwK@5BXA`Cw4-W04&a6E6f12YiLFmiyy{ZLxG-dyvs9Jv;bDs8LLSeD0+K z>im&_g$qJ^4G&TNjBJP^0Rebpt)CFb{Ead;+wEHHUk4DjJx?s)4@N{tb!;UrC9l32 z8^dtRT0^CoO@z1z`gVTY8B2ef{efPQic-ku$q<_YM$vi~SeeZ~5?$s+zp&5J6;+#U ziS*PNe98F_s&Taa?HNQB$66nT*?OUZZs>CX!&@P&BvU6^vYSC|-M+53@YOgT5wn{GX*p4GR!= zp}X6Edelu)P;@jreD;e#3#z06 zXqv+`ICj89KcB)+Sxx6D)LG4va&=TQ39+-&lpBl=oq%#@g|B~q8A)N(|Mg#ap@V+) z<;^g5zM+^2Lhj#Dg+0GlyD}dqGCFv*X(a_)`g2|gST$Jp7kiwito(#8^Lu`jOJ@3~ zzCab1Ut)#Xm1_4mHz}z&E&!&5GnYH`r{U<B`eJ*T}ry2xKVY%vortaqRHd ztG9D78I*42F=w^-d9{8xH)aEP8kr(fVkttz)w-WD@}14-`AJ*>_PbHQOy$q)AD+(6 z%6kTsgg2lTMROh7D!A`CY4j2}cfauP%%rIZgBBT1H z6%ZSt#|^t!?yynh`goaFsvEj>8HkdEl9VcNH`>)z%`{fvuzDF+>%oaXoCug{bl|VI z?=1&(rcHBI?5o{mc6PL{y&+6i1G&f(Plm}uV5`1|qptJMHGF_vS5_-q8ylQ~4=+&^oTzW&E|lu73P$_z`e=3g0$0D6@)O z_m)B8)of+*Uf(LA-Pj67>#>(=v6 z;Rwyj6;Py;wMA<`^M=nwB%QlCzO(b$a<7~{hJ>I$7x03d z`cKz1Ip@|&<cPXpjvPiLJOoIL}Q1(Ikj zPlP~^&SYvcbgH0BeW8hVQtpV^w;t3RNXlK)%^aaS3TDg4FeJ+mKIJ9tm>kVfx7>fu zmP}`pl~hOX(Q?$N=<8vH%yVYC0!w2LVImefhZeUTpfi;pvw;LSi5s%R=OiuCF&=Pz zwnljJy8`sJk*4Dt;Bg0Q!rso|E|RD>-KX4izMGZvu`)an=zp7iu>q-~D{>k)LaY-Q z8UVDL+fr#k7>OT$-}fxt5g7VDaPcDc#rp?97bCPkj>=*gWg5@)%rpUh+yDMW$tr3P zkHLz$oqR-58O?q@dVkvm{(9|8(jTEX#%8KXZ?~tF`MtK&E{mKgT|IXC@|%&_?p*Lr zxanx&^~6Ctk3ic4X2r!XnW2DOz)ovT*n&{REeiK8eX`MIH zb?fzlCwV?~pGw8S?o|t~d8C8~NKepn6enh!Pww&4ampsg*Bct#Z_h^)+8!mB$tL5# zxt@@RJosdDJCXl-TIf*!(LRZjvumB&@KCRr2_R-zQA>Jag(*unTO;O`$@icc>o}t1 zprd9vu00j*x+bvGjqzs=tcS%=+C=hCx30%F)87V5V!-7>ujeCXmObNG-r1y>3xGGf zSLQsr@(hZ?XB4PJI%z6xgat0ku>1jjeN|pXXY}Pm6xl zMQuE%%AO>=Mkf09;rp@|8nQ$_gAD%1Z-I9@A6{Mf2j@_fhSL5pg2jA4fsIZMrtsVRLk_E8w+2wFMWOwqrmi(p|GWqQk0!t;SJ`j;)AGgRH6k@<6}t}T!b{t zwVDDW`LNAAHA{-~hmg$vIFEuaeUOij(rne5$ROIvr@an4McTRTk491b9-yHu12X6f zQ{QF@>{S;{x{4(*tP%!8b>$@Yd91?P2m3ndH&P8Diac$vyQnRSbgYQH4%!DYZ1p|b zc|O3jg<=&t`SAY0v19Y68`1e~`6#`0bo#U3zc3X5y%)im`teCP^9Azw`q&>U+& zz(#Kl_Zy3fV&2|5{_YQjUtT6VJ?k5&_alhb<5f9z9eM}pIkBBwJEJ~N zlo_4<>VF<}PkuOWR>}9(6nU^@O}0ymO?7asH~U21*Qt#`e3x6JZgi0vnG&<|oJkh%=ONhHTsMvb!*QI6J8qHe zn(&Q1Oq_UD)@-YvMn;{CKeL^Jm%W8SRBQ0opGqD-ffih0N&T^VuciQBR4OJ%!MfDJ zPIQ>-dOTrbsTe&dfvP zm7ciwF84TGZ7HOWe7^2-8w=7eBfMWf=UO4J(?1&K8!u(~=+-Dh>&@uA{?$Ww?p9GZ zr~lIEaDO-bm12Vt%ZDx6%W%U>eE8;zt>Li#RGtFzUKY1~zR~GK#F!Zd*Zy?#v(x-H zgyD*ZPgVHr;{n7ubVDJtIz>ErqAI@^Xm(&QwqP%6*B=}; zlF^o`7CwgOSxPV^M~fT(J?Rl<%pv5`Nki>9Dttuy0ylnTPia(4(|VX}r@o5eCxT0a zZn-yrC%x06+gE?gf<-T$Krx!bdfPGDK<>@msa#TN^vKO0nRQh&90WMjRg0J%i5t{u zikfAUPlyhJ+h>nyraiGS9CcQ&ZDOccdOt3f*B#m}`>!%a45ppZf5IEfpl0At4We-` z-9r1UeTE@wC!i>%%5}f(*Nr8`J3rO@fZ0NGWxMcELXYYX5&`?;{duidfr#Y)vwcRH z0yo!(vLgYHjR_UsvAfKRJ*m$t*4R4Cy7HZgag;Nuez@7AP8T~3yB^W`(Tx=H*KzFF zlkDwjv9bU@<-UPKOU^l%@AKxbd<#kvt0iKOpV2P>gUm#{&o%R|6M$6f_LTYB;G-V< zC;#6QlJsPgf!ZNAXtNn~eVLyM-${<$8?;P%izkUGWm4TzG7?t8ezDD?!uIoW3 z9a`fCQ&Ea$Q-;!)w<1d~5uT)wc<>qtWk`ksK?Q%EY6;@xji zA3W|hI1ld$3I%*mcF29fp-&rPFq*L3z4qU;`4X1ev2j$PU!0Vj%;NtOl6Rk*7zB^j|cv$5? zgsCfagP7vo>Oij&7o=7gR-%{s{eQ9d)^Bk%U6?QuAOs7+Jwb!JYaqd45+GP`cXu1y zCAbU{T!Xv2JHg#u26uMyydlrK-|n~j4{ZOybq&+g-Bn#x=bXFlb01A$lZ+{{&(SQN}7%87E_?G zjcc~#CVuPYBSSG&K12sJH~#X9M^RD1dr?w4d$oAoV)5tO+)t=ubfs})YSR=LdE=>C%g>|{V!_e8$0UJW$3a1vIn?84VX$JT( z6pi(~VMj`e<{cl8Lm?H{xwy#x?QZ_ife;k|0hO@VfrR_jik!T>ZF$3U^w|5v*Axhm zK={u=jI*fV%e}13le?at5fT=AZg<_6)K~x9O6UU#Pe6?JO*rdEsw}YdgP2pj z$7^;eoE054nlsLnjcktCGA?dr3)xE%E;4JzeMk1}52dCIscrg{3#N^-Gs6;m54{g{ zoyGwiWjT_%G_Hv@RV07!(vnPk3B>@aw-bbWXxzb?EQEvExzAx!&kE*YX=g{Fq#=|`34QnjRxw=ecAK_s-kQ@Or);epKSo$bWr$1klMT&3T;(nGBSUuvUwMnh~mPNa#^X~4~T z2c~dd!_oaR1ULpX2m5c&{dn>OVy;1vM)vXy~or1M8cgD2^S6dP-nL%lXEk z`wUe$t>0P>2Ikm6VxT7Qr|zZ)vIeXMh6+Gx7m>um+4>*6itlket^7|IH=i}Te+T}VWXtyYbN zx-`Em)VTSsZ%E`Bo8TkJS~)FVjp^afxojr7Ql`>)dHKZz?Fmh@dC}i9hCGz-tnzss zxp&`4d{ygkA;qHoXaQeYIEZE%9{F9TtIw=k&l}*eB&BA4~riiq&4b zU#v9$yf++{OHA%&ZjXO)*8UL_7333>r67GH^`*g`2}<<9!~h_hyB)EZcb10{Q3F|67ACJogu;4|#w2uUTC>ON zM`R};CL`Nvr`}ci*Zf_=VDZ-XU>qP_Q1)tNH=k;!-y0dwXNP-gHz}MhGFJ17w3+sP z&({KsM*j1SLqmb{?a6(S=gF6pL?*7wR`F2e}0DMtG5d#fXr|>!?DvhB8{`;%%u5tBXQ^+t6Qe8`@K88TpnetkT&cX|-Aq z@w)n?Lye&-z^W%V+|ukJEhr`zE4 z<#E2PZ&tT-r7FS$2%}HIeD&r^_q7D#XliZ?0-U} zf!2JHKEW28s-#Q31ID|+CSy^9?%BR5m9{P45Z$;-u@7=I2gNk3_6PeXMo65~aXAS;WP;hWKE&dD{rP)HC*>kJG+TzsgEfiAiE~(5 z{8KLu+1=Qh0}_Nd^M2Cg^>WdTj|yWg)7_1uvYo1F{P=J_*x2(Pu^9i+9oFY7m zluRvRqSuNib0_9j)$N?E9^UkY!LQ|-w7UCL0cCqVa0kKCUG$}-?6lYvlpKhzZ9J8h zS2)Wa6`^EhyE79yT=niGI0rSBOV-vHPbm$4@)E<>2-8_6LF5b+S^9#Ww#oYIBl~$* zd-3-tXVQ;n4mbsOnkje(f%iV_h(r163pSg)6|=|=1eg1#OtwNONt`^x$+OyoAu?~b zdQCjkF%rR6MCB+Jh3v_l@(VM1I`e%Wln0kCe0_A&e$Of!>e5Q zXk{Pq4Y~hAJ-;7pbp4l~dWe#f1Oe_du6FOu>$)EQm=01KTFTb6&@S9^i(wTGsvmQw zn*&rF#^W1as1^&!L`g!*dn{blcmLVqJ39`nXyS%!=ICX+|rn z>s}M~jM5bluiwaNZGF{l!ZClbGPm-@+Rx%^mpZ*WTqrUZtd99d;h(cllx!_T4g4t; zEzKSB@&%;-wp--wsG zuIxvqFwtkGu^Eyys-Nj8{@I`>wE;kqdZ|^)$&ZeXX6KeIYSyi|xU5#7($mvny;3|; zN)2YsRBHHA3XqS~h%6nEM#7bSYZ~NHJ2+dd!w(DPjWqTtkF6_e*VkQjuj9bcjLqCH zm!SrWm##ON++dlabh${Ph1JYhD3z3w&Bh4%PjI?GUvrGw8K#JhWSdz2QX&h+Tfy$ z*cZ(d%sBb^IX=f+^u#^aWut-|JT-WGUC)2;<#{^xF7}^6FYq(ht*Ecu?v?R%Z^(X* zZVojbk7wq*-}&Ux62L_H*Wa>atNC|t24^!5W_U=(_TBTM_0dN7zdY``_ag{a(bz}n zn?IbTRcp7k(f*!C-g9aP#p$r6sFqAeM>vlf-Pbvj_>JW9`?J%%LDCKJ)0O5&Dxeo2 z-%!hqf{G&$DlV)r`9%iSH&+W@|J50IR6N!D=UOliO}h(~bo*E8D{f}^g^p>NBai^V z*1mb*_3&Gl_4vk?Yx3|rfi=)MHqe)yw%V5A5ZaFNdDuEDhAVz>f89O2ASvWw$-_=P zkR&(~9c9qdXGY3Eow5l`P6zHw{s2HpNaJpoFzf{YNwb1IIO*^sd98N`S zIe^sBVz3!RjtupUjn@z;-g5cVX!%%V>!8k;sFVaW!uymYb)7?Uz0!5*D{uxcU#&Kn z+`sqM;h0e1U_P!V%_+Q1lVMA!2==bbFO-lac6l9He171{N5BAlT$sSpi1SmVfyHf0 zV~s^bUhF_%E9?+3Px-DA_(%asFX}DS1+E|XB+x!jR8pk{1~*n@*Z{I^FPT)t6%Q4l z?-6}}nOhGYDI-O+K~;2;0U5>6?=XOF(INPk9j}Bj$0MI}5Q!quR<^^}gqBBf4pqSF z2+Dr`bnP4Bk7awAOM~FOJ{)<0bRY`V8+mB5phe9Vp{K8YJIpS8x-J`r#x0I24#QrN zZb|G?Tv^ zHugMk$fq|Gsq+AwG()~O4S1u)EP_ScqQb#gR26v9hypjxjMja-ot?SpX)&T>FvND2 zivB@ojuYwDiM*VtE}kfbCZih^jM7;;HN4^y(p||1rYs1GfUTr0umnD_1hWX7bfoN)7g^K!Ovx&WXaN{ARVSsLtOT^&+mtfNajRj`05gy zp6UrSb3Og+*9A98ts8&=N8k^~y%(uPn8Im*cx$$?R%>Q&9~`9<8!X0!g#{~Hq?LR| zoj`!(kXaWNRqo)&!C5#?If)wYzCz+B&UN+Ek$utFTlJfh+$ObpV~PwsLqjA=sAvoZ zi|3JBlgb#f8+r~kMo`T?RmQ8a`XA&e7wiQ z?N|#Cczbm`vep%HT))VN(F%=Mn1m1izjxzU;X7P^^@$e#i&bwK{-3aF{lsb4R26ma zBdbX1YsDRiid%L08L0YW#D3e%!zMuqmG@DUVlyA6_`S5*Q?osF; z$D~(Kv%%reXu5b2Wx2+9!k@!@Zo$66nPCfWs)<93$$Hho->yhn%OfK6U^o0 zpQYy^7pMcqSTXarQ%3gk&VrbiOx~JSHApo!1f2*JxY$AraO4{PMIFLzM@{ri6T;Pmv`t!ME}N!77}!D6Jyt)>2w;I3q3LUe?hByPuWS z=Xt0<=2n`|$3a-&8aG!>{+8bnV7Yo@2Cr%;&~$Rc}!S>ncfzhzfAyPw744c^O{mwD!~D+2`R2eU~oy zWqW(XnWY65L>5*dwUpD9RY3RcjwV(C`FU1FnJWHN{Uk0f9;Xzw=**fZ?Hdq)fsfDg zdIoU@$~0~$&VB%57~@g)zXZ4~726TlCAckFa3e26^{7-AOQ(NI0X6mvt%XM{hd~5h z0nOK&Zy_#A!|h6Z#|cWSc=$UO9>19xJuBO;KK!A`2dejAr?0^(HZuv&e(wgib91wa z)*a2P>h5`t^ke0%9uEWDsYR4N!&KatWi_34u@O1LJGgtAU%4uGXbFqiZLy!o{+j+{ zT8Q6p)wvN2_%I#7A3V=mC(pM*A%N%{1R%at{(D;UogufpO`q_{U@V!Bh~HZ z6y;w4xV-6A!SDO>ajA4vxZeE3KtW6UFI;nj6z<;^*1eyX|6F4>8wFbbL%e}dZ^Zh? zcvq4*EmOa(e@8eNO&5V=a|j-2Key(d9-@mzGk>@B-V>7l(Bl)?*rUgyjq87u`{#^a z*dI_wz?i>jpOFY6&je*&l9AZ3>T{r$2dvjRv$K`D=j!)RH>jK#sP(b7fPz`)Th?PG)bAXoNvdE zd`}y?*Nc;SY7l1)3Ge3igNC|5Vs6N07+w=3n>SO~?^Vs>cG4@ZyLSeB6ESG8-53H@ zWbuHGK=pxMN}|MNcesXtU!C0XJ@n7^3t)#M|C#^&mokpNvv8YX#ek?SJydf|kwIri z2SS-lYj&lBT(mQUDr3dL``0<#1}~&UyFL5nnzTJvr-Da1a>uEe5_^3L6E8Jf;YA2AUHG4<@O=MN3{Du)Okx-&t{ulb23l zFB$GQNFTRB?l{<=93?&w1N_P5wJ z)?IAfmI#Ib%huQyM~EEJX|_TBOYEYj5ZMv_;4bS(`T>sDpKq8MG-jz%Y(a*s&bOov zlvugW5nktr^kMOR9}b#tq*G5cIg-!PB|{9InqA+wSs1Da>hj6QA9blVzB8{E1oZHD zB`_RmZ)Q*wp)Pl~RYG7^_mt*$A8Hd@(QDE^$y2hh9=zXrqfdQc(VnmT4Ia(Je>tDs zP4LDwj>OjnaK5&gD)WBJ0Vn_YMfJkkDTOd86FZ0U(5;Ue^M);4l~Ok$Hu0wEj^;zw~37x7`D>0Qx7a`$tz(B86af4+}#&PE_Dx%2lY1@N6Gj@Ea zpo?qz?xirfD{3DQuOox)_Hffy1Gnv#7H+qUNUdqk4}7R%HurjdUhJYx@ol-7pt->) zck`WJCRowTOvnh#pzg7|CN7sSd=a#fm)IUN5hG0=+D=s+(s(BnK|Yj}U*1DX3H+x< z0Bf@w4FU%dS>Nhgow1i1s3k+cMsC+J>cY$s6Ani+B0>$x|t1kXQ10&!}_p+6y zmiAB11$rbOofvfTkio$93i?OCSLkMf_!3#ptO5J>KTdW1@*jt>FU7u6nm9soc;R%a z8|3n*0~Fe2ZO-u?X*A-*9v8a3LKfd|>h@@3=5%}$*Btmd7@f@D(Ftz9U;Sl%E+Fh~^8o)0T@+AHC{v-cF%M8$+@@D;gJ`t9Ld{Eztp{zkbm@5x9}VL6_oPc-8h-zZvTeTV${ zslD{%1q!B|lUSfQcm*yr^cDC^DKu6vDX7=ML=EBOqdZT{)r@r?nG4+S+cQ;Jh->sbRCIr$tA@U!;=p)4&C*M*W+K3cm zQtvn($`vsTE3?ohB`2%DV@4rB)fpk)UN|~NM8S8r*G%(wOCtRA%i{f&9lF}lnnGxd zlTMV|`<;E!g`c}YUY7!RaEeuh?$(Qj|8rmnO{6?RDVTlbAZvk#& zEZc_^^1cQ3+97!Oeidaeh2J_AsC|G6zujJWXA{fLw@zI;s52xhC^WxAZm^}%$kR`G{SA&l@&b2t7I z`6!4uxpjrG@-Us&N)&~X#;qk(4z2vVk_T7&Tcd7GfFQ8ZBuu+w99m(J$9%%W_Zapa zB?DqWBpRzyZpsoD92RmYZOALn4+q0lzRuM;cE(D46Bc6#LMAVX=tO2q3$erXi7TJz zaB(``X67)Q%{kqoYjF?wanbr)v!ga{&Xm;Upbc*dR4}xE2Tu!s?%=qt@d%0V4qzz> zWi>Ws_24|o5c>R1!-*;s7;tOb;R4a`WIni4JioC;Olw(+7`ev=YebX&I= za7Hy7rfX5=JF(cWPn!2gE;{5X`rCU|_lXWY-IndXhMS-3xkvPFA-fy06}n*&TH8yk zS>L?#uvEiQY=PQmyH0Nyh_yC@hsYPpe=6uOrmmZHqCYANc+~_vNQTw8d>I*W+ZTXZ z=%1)ep*<74;Y4zq8>>ACyKpdgQsukpq%Z(zwl?RHM`fT@Y)z+RDK^S9IEPY{LYw0^ z$W^)PN^&w)Mkk*zeoN`6h^mWu zJ+i84h~e-azd`ABY$3ur4whIHf8q>MALe@nC{9;CDxl_2H^x+`0O9t_v=%QOSb@#? z*=6wT4_O8Jofljf3kTf&bP2-;f}|4Fv*J88@#;VdQ~lrKu)mMKv!iktROwFxpDR3h zsqnw1$Htiqvp!gKa=8Zr@8NN1A^5(j48Ds6e&$%H71x zO2jQ!D3~~Z-R=S(GwYv2?KNA+kdKt}F`tNt#-owfp7q?{9WZGWKcL6M5R5m;7<)^1 z%RpRZah0Ky(K$Cv<>0+AVPio94k7~hRkr{En8D!~^KsOc2(i`sN3oc4Jw>p7J|(O4 zBO3`%?97PhXw&JwnicJ*odGhuvC3KVxu!diV@;@OG4pp7JR>cw1eli(M*Ks`jZ6fn z#S0W2(q$YZOzfMiq5@yz7`_Z+7EFXWcE6Ax?2&Ds0_<|x;f&SF=MTIWKm=3p(|M<9 zpsaRbP%8(s>5jIDeHmjH?7F?wZW}CK05p-eldf?dZK&5OKg# znoa&)=dyjC-L&1I|K@ zKZNF^H>j~xt0Fyp0NOce?RhXk5*@@Bbx;!zJMJE3N&6i|_hKE7ta}U2)#Z7eu`4zjBi+?zidM}L zSp%KLlGCEqeN&CA;KFCELpz4|g@LcmZdVl!OC`XTUjmm@?UbWho;@W_=e?`2irxw$m4A z+RSOirEv5NfCB*#9!!yh@Ye9 z-sPy88prCZp)XL=Wx73tXrg}u^fUuVX8-KcbaKdl1*~bg|0)EN zb^qT_p2Z6wi`f6`vFEY&@qY)@{24IZn|j+=w2F{9@b~P;$a13A$$WV#&Yr)yN~aN7 z)OpWdAZeXA^uH?C403+~YtpC?%+}v3Q5zrTYb<*p0$8bnzwL8xhat>;pK|EC{jFqu zTbKg%dOPE_4*aa&Up*xaK&!gA-158st|b<^5Y4FB?A0pU3a?yYR$cV1TInBvB@%(k z)X9M{?Kc9lu{wdN@MjLANB+T`{xnD5_0?V+{Wlw1!oLsuB+l)Epmw%3WNS)D>fE0$ z67Uig)nlgP4@?xvXEIsvb#{pp5}jz{aubL4E{FZb$&mSv|6IaG6QYSxhxixuv1$4L zem27T@8@~N6$$zb_uN4Xj8}@#hBFcX8H&Z!iw0$m2%ukj3t>mNk8MlXYHXQyvh6~8 z{tk*8xL-U@bV0l4TUk%3<)q|eX!WwQW+b7tmW&Jq1phHSQ(S)bb=2$uSXNU$6V6-U zNGG?-@I-#%E*LH4Ab#v_jsYoL{|_eT9_^R$I;GlH4c?>y7jMMc9oDaasK^~L>ln;y z4$P)ApF_(A@Ft6(xGg_y6qwSi90VkQrR4>XaRJxA!Z8Oze}>Ieg_?~=-YhDWx{Avr zlPp>NL7&Lc8Umn(`^Qj1g7Qyrx3MkPKE})OnRtc940#Sf`)g}y>A~aInDW}LGvq$r zux~b95VUnsQ~)AfZ8y0G-5ePIS7e5Eq&}7V&l{~vB!sh?E+y7qU;D_@%$l5)9{o~q zELKeFo6V@_hqW>+H(oG;BC%tpT#EO!w7fkzp}{O?bYjyjdFmwZsHK*nN&S7>w5~_y zOsk`jIw{!;NRoNjSRwK19 z;Q$)?)YY4#^cM{&O}ngy^|b-9A#tTVZUhJul5gg&>~H;FtQx?GEqGwdB=!!LW+q6* zWS2G|=0cdFe0g{txl<<(8^>KCS4+zSDPbU@x|=@0BsYR0#At`2m{1Chho?=h+pDemS*^CxL2b+vF&bvVK@ zuUxIq@!9=}Q_<<}OG(mPAKFh$0uotPq~0LN7`WXipqlZBMsF6P zo@<`-w}>3Tz1VvXqa>XnqJ?ZK;2de$D0*@eTHZbcdmNpelSnEM6x-DC{>6EEgFznZ}W8@ zTlUOE?92C~IPDp$-W$TKq5~#KE8#kFELX(0-|!_}BWSn8{Wy%EV4BUa!iAqPSJvfV zJu7V4VXv`k6o>8ehnMde{Ahf}l%+M^~y&PpU`K zB&$bOFA|b-fzDe47~|>Y7mJFAtFgh@Md563qQ7suh2g!aqpD7(^l_<8!(&CJlD~PM{QdZqobDcZjKc%`rn%W}U~XL%}SEMhd5M zzHR9CNgc**F${awLpsRec@u=;s$DDaUU-M_G3gUoQsm^{5KZphVSpaGW^(btgWoM@ zoG4|E&!bGa1tr%VH0abZy6ZI=$9b{{l?Vr?RcO5KT- zReB7!tDn4n2sfU{;y$5Xv@p*yOowYP*JO;ONnPJxc(`rV1YRX!)`1i6z|^GOO}&Gj zjEPlw*dByBx8a+F?X66knZiDEoq&{1(0&nS-ehWtDBp)4vu_K22xdccln+mCoitcC z6(;ij7%k%JhCENH?Gyj5WMDZv;8&4wEX~(Exhe)gHR@__hE@2SbOOCr#cUaYR<&}g zLB~<=oIk7nUKN$rEFt!h06_Sj+uFY9tC_qY;MT;WYtH$|{(XcFjGzzWZYvjZ8jp$CZP4S283CB@pix4=FWS z6l8Pp{^{sF{%%^i|LSkng{bZNefl`G{?9RZ83k8&@^w$ZE@X*M`#CJK|CTlh9Hm4-Cn6G;Zt} zYGX;yHzPxhRAVVEW!`DuBiI#=M@%Sc(g>bmXD%~(yQ;nrY{G93p^_`bH17TZjL68S zC)5sNbcuy)P4wf>43!M#yXssG3=pC`+?goh!` zOu~!!O)z_XRQ=<+Y&JvYHF;{qm&kH&nR!A|n)V}LY)vG161W~-b%Dhh2hdm~& z)_Krrjh*(+H4dJA4-_S!Z}Sk5D8G&ju7surJUU=$BQ;szq;?toXGgxbN(<^kGSV7@ z#$`wxiV-Fe5r32O*_JciJ~dZ=@4J0kw;H?gH6 zI&37@t0M|Fwo0LG&@i1GE6P1gW9_xl;jk>((5{4MNe>p#_UNF}wgqtfRH8)*Df+V% zVsttSTKGC1Hjy%vpUpV29?i4`YJ#bH=HWY+8c$F{n22I9%$^v% zO-9^|8gMS~3$ZF-#FO>*v)qGb=ov=G=0${-fhms1+l5BEwM}5(Ej9oMvvPmd@YrH` z3?c(&k5?RLK;vVdnB*ZM7KqIkeb z;9$)A4gSm@*nqkkQaq$?aV}QK0@b3X0rzo<|D^?M0?s`0R+nI-#hQcZ!k=WRtlEAh zsCW>_wd(dYHAj&mt!%D*i{l>yNsS4S)#osqvHJa`1Ei>|`Y-xF;IcUL=J9dbwl1W2 z#KqAf@AA-}{|5#x7{x*K8MbxlmCDfmTn9Z8q)~>pVn8?7tqy>ck;pLrwD`>A2o!I| zf>iKXTaa;@DWXfl_0qGkSis5sDFmb-!4BOKDX)G&#L%EHRGL^Ibw0f z(cgG9I8g`ZpNrdM-|tSOV;4FkQ+BMj8!(Ia^}f5E#z1c1LeJeG^9>~@ z=nZCA{DoSAV|B3p`8^AT`|dPz%nm)3xcESh(tiKBnYv#NyA(#+n$~KB817OPG%h^G zHfF@@;rI3kmKKk(K`D~DnD(sCv7}tl%&Sas1qIA6U%teWrgDUxXEeH6)|U+6#2QxFb zfWK=2wY3Op^h3K6SsY)WJ&t9ff4DT0wMgjrm56l1PUg!?;+DL6<+~=vA~@m{M$djH zZ$A=0_y8#*YEH5WQE!y%=xKE}z=%A42)H4T&l|lbJ|b`tbX4H$Tqq;aMNaJeahnKq z7BJxGnI2ke+SLTx+TiUeFa{B!sq&p-qp_XS?4$`jcXn{TaH3~}T5sI+3ChZT)g7Lb zAyGyRZy>maculIM?cQ~Z+@HNH@(5~B0hL~3FrAI_e)2}>GIchTxGK>_ zS8(;r@lM`gpOXv!GRI!u^|8h2c|22JzS4(5z2-M+U_y*fJ3;wj*pMXs4R;_g5Hdq~ z#8nj;I6~k$JS8;EsVGfm0(xNy>3~J=bLw6`=K6Xh39&m?8o7AdV zl#dfBOHTgKFX7oPUcFup(Kxz4?X=YFsV-%ZHdaoQ6n&dAcf-^{m4KgJp`Zh}V4bFJ_s_5r^s{)+>e#t?B``Tw83mM}=My@i-b9OTTcr0yfU+${CXl zYf^xzAgqRfFf%b!S+c-})QF9DJ#6*9_Ika%%hqon#^)K-PTlBUOqzDl&nuN#T;UB9 zYmDrr`51qp5+4cwv+$wUeZabB$TJ#b-!4^K`0^ zXp+%ZnG&1d#~HeE{?MULgH)7F6!f=TKYP=x9aXL`P@zOb?ic0DVJd7sts-YrU^DM| zS#-Ukt4Jb2Hl5g&m;#!Ow(}#Wzj{9)@J(ot8bPB?o6Yodkne__%^CQ{rkZh8WWc@g z5iFcx0MOCf-n*u8|JxhdSPf99!+uu&#w`3MwCi{5S^6pE(mTt6#$Udjp*KU<_B!a7 znVMMc!7IJ31CpxsJaYkZhGdc}&})pDGF(LrKALwi_0F5;0(GLIPgqzRFj-6UxY=wA(L@Wt_Y-DGx@a;tMq)G%c( z`*emq`BAI)?bdJKf#j_# z)^Gm*$q6Gk7eb~hz4=Tk2ua7C1bM!>L0N`kjgP6Y*2|`d+^byOM8xa4ETyW$8Zw2W zar@ix(6hnyUbJ|#O{-XrJWUq30&FCY=n+7slrN3~Z5oCzhj@G^jzf0sei}3G{k1R~ zH198=7s9&b3f{SQ1BKGSpBA5uR-hVE*DdyQBhVxF)tf0-2vK_`_eB2ARsSr+XUZ3P zWZ_N@(u#muc}Ouv^JWJ{Lva0Hepnsif&%oy#trkelXLm?&m%~&2+ENN>bcV!48$xW5by-?3Hk?rpxF8UF{A)MgegXQ zA~$4_>VDi%`>#nAM8NaUk8Si}cK$C`R1p-`r@80wx7#2zs|<@3x#pWK0&GSNx4x@- z`+ZS}Y;B41I;4x<%eO~B6PcE+^khN|O4&S}TmAi8EJ?bKRaVa9}VkFuIU%uIU`7H@|?8FlkMW~ z1whwEIhOAD;JK9@VP+?>wUg~;$Qf3bnSnWrlv{$D!cBb9+=J6=l-fctIfjyZr}ofe zf)YD$c#}@nDtRRmcw^C87DX+@dFxT#zAw?!uIX=_4LrZnNYesk*;f0*xmb(E`iI?% zMt@7F5Dr3}l@$BHB^z&fiA25adMiENzJ7-{kj7AeB365?BO?#>dLqe5l@4^BK8j#l za-C26EgBPQuz9`HZSGpS`O0B zO6+<@L2RbC`3szU<|jRVMQ3Qwm0YfX=((OpKD8vxt+N`tS!&p}4#+d4| z$5AxK$YLYHF51Ew7JoP0nt0Tiaq^sxpEW}phhf!v{9)ctqV^t=HjnjRtEPxjg_N9?iymfbJlg|7w3&f$nYJg<#vxyz^hcv*eSTvbe}4twZtt{I-GkXbvJ zzgH0k>Gpq2rHdth@~~PCWANriqR%4GTXFcFp|F zbWPgha7eJeWb)Ig^!TMmhagEa$W`ny+S&9nDk)l2u^O}y9l-q!l7cOz;i51Ui#rfs zf}CX=k(+or2_WpZj!t#f79N(|eWicG3Pq=I$Q+rNf_iqFLceqQOL~gP(TEJ;k24av zFI0xQvZD4fe);6ko7tUU)do^g5Nlwx!Nkir>ieG7O4ip}wIe}a%bbBe)(8CUJA8v~ z0|R8xN7X0sxZ$*Z)653B9;DXR`H~k?*O)9ejP^P(w9CZ8dadhjSo{IN7Pc5(+NZ9x z4zdIXvYgY0980I_Q%Pcv1KUgPv&G`)1wc)=OThE4q5It2cVJTw;!va>E_w!MyAAtU z>ObN(hfxb%!wWgE7!JRXD-LBexJ9g{)9iCV@cbY&V{TVLr**WpNS;MuyOC=YcPJpZ zYGCl)jmL*YUuu0*a-5MOASjoYH;gSF%}Zd4 zPpw7Q<%pj*QRiq-~N$ooX)E=oIK7RWDWV7ad(@V*-yDB&?zf}{@v{w5FYL_V+ zeQv@+F|AJT_^FO~PXF~6{c}Jl&J5A|f>Ey1e}~qzn0oz7*Un@q_7u;MJGGQ#f8l=+YYhPEnc7p$XBma z8?ILB+q^X3Fbb6#zjEV*x3@c5$X4<98LK0TLo`?!(x z1u9-FDBm#Q^uo6C<$f!Wvsp@K%eu$`78C&25D$k&0^3jn2g>#HEy^?#IN|p>#vMSr zGq54|xY|Sl;h8;NOBlrC4&P05TZ>`2uCgBrbO9nOlpWjEo!FmOC~{5A*3Ge~w5`!B z*>4=g*Qp9UD##&TT_##pUPB$N9rMAEzdAmOUtO58E_h$WBU2QunGdSookH#asfe5= zY@`fpGM)DUPBZf)$)N{)785a(l=qh>kd^n|b09O}VgKbhZCm;TZyVoJ24dB{MP^nL zOOCOQ)+o0gn-563eSQL=VNo`|G@Vdl&S5vhfU+zSbg}p)fFr? zRdnlV2ybWDJ}zIIg4j6>j9%sEwH<+7PpI3%Ma5{9Svak6a+$*SP&wgSJSE{41@Y#{O#M)aWTFrB<4XdKWQ)a)rYP=bXt= z2^TQ(D*D7eHq$kBdPhwc6H=!cG~^Gd!yBrJRW9qKS)Zq!E4(gSi40D+DJ(v3YG9yX ziKsB?e=q6*DV~D9j{9pgQp^bZhQw53HG#cw%zeGXm`~&W{jP?JkL>MAI70~l9;R^>TV)+0)rK= zOcKIHro?A72OMsqF0X_vpkDebul_!JrmPB@!=$lj zgTbVgC4$@B*`O3)g8!F)Vq>ylZYTKjM)b$Zldc~E>wuDs^+6+l$9fW^mBkz9CF1D- ze8uQn2_ol*l!s2d8u=Q1cN*s#`E2WNbAG#k=QT?XlMOmv>}&rtITa^PLl=Qkai4$Y z8FxZCdf{a7q)FGr(Sz%?K^ZP&?7TS!3VQvjBri}Zif##UR>&};riD7X&O8|U`KjvF zQZh)hLatcSJn$xLq7Em#Mw?%7!Jx)fILT*0D&}A31^}%_%w9YjzA@-@&o8+?$lPbW zadI;iKWlA(g&hJ1p}|1zs=swILLqW(v*`N52_8M|wOF(&(JMD~vL9?%Tz#{c(>F>B zS(M4%-`~QVasA4nYI*joF^S-;oPXu3ka+Mmr+r`fES(#>U>1EqM^ypzh#V4&(<)OI zwHy@US0#UD;Rdug)<%Rxkj*={o8}9uNOXbsD|NMzRnz zO8dgf-x1Lp27}9)2Tn|N?k0@juYav72bu2dG*j8G^FS*OFmjdf-fDl@caVNm%I-$y zE#1w~HFP)9HN+6Z8K3vT=XuZhzrS zxFmcD-n`i6HmGx%W!2#Rrr_WJfefb$;45c#`wbjyz@}65E+4nPA&*MqmC@Hn$hT#g z`KeZX<(@#Dt50vXW2Pn}P)TxgI*x@-TpM=X9 zOmJ>*=-spBN9dNqkFW4I1edYm>2p~g=8xJNZpq>bf_V&(WwPwSUQBA2j|H9ssVVr# z(CKjr-us)E5MZ(S+Etd>LiF*7;Ktnx(3!}RvbuH-*kfk#s9pn0!vdm!K2cN*Ny8mjpwdkmZ<>M2(^$Y|bz9mk~@<#U!YFpkXH91Xu6;dA^%kx3l# z^<597Kfl%TJ5-j2Zlwa%;7tN(mfn)M?wllHS^P(}XV;mkpxGspgto2$iy zj2;+NR*~C5uf4B=QM9viH7Akpd5a;iSZ(_G9EXon*tu9BvXeNmoZbztN+%SmQ~6l% z#6^cFzG{WPDnxaAWBj`)$Fk=w;>FvellOrb9&88pQyJ(RQ;lwCD|f3C&zrK&6#ssN z7-Gc=8HWa^1F2f;MHs|QyOYO9jQBbG@i0GpV%opw%KWs~;{BO!Xe59NBpHky0@-ZT z_4YdbT$jL#VZ2}$%%%wEA?g26P)~gb4LYaecpTT|2(-V?u|Od@#sWs{yxXZVFx2Lq za1DzbbElt$QDk^qFdbmSy5lk}`JCO&wT-XNlXF-a zO-DQFR%SeYeRkv?Fn%AI)PC^lqzgzrS=x6p*%)fiL-VAqfLUJno>$9ah7IgZ*`F>e zo`}}kA6a+P-t%-%@?lelX;!59G_G_|YkI-wFY9uub7#=#|B5x*Hm19_-a)+U*ZCT7 zcU8(lKzU0%l~-1qoMd}bfx$~x5k~XteNugGwyU1ey8Vge2)b9*h8w}_^wr02Qx>_u zhUy$q&uW#|JPae(6rN)E4Vl4#9u@*{?Ms$|I6{RA^yVVGue7M&pCid>1P*M%M6Zk+ z(geXrK$#Rm;U`F<`sPSUa}ZAF5lu382Tam@?++6G7$s%l4b=8L(hSlnmx7}$OTyuA9+HrU)FpXSTzv)&K-tMU7@J3(m+2Ha3FsVI; z1DBvTgBl52mlHv-7EF_R5&1U~$Z=lJKkDwAEdA(;%NFyqGLZtmN!+tnAMQZ z6_Re5I5^~uu*(U+iJ#T0Gp+&gzS~{Tf?%qgh)Y0dMEtYWyJ7E6ZH${^kG%x+V(pCb z7BDZ?gin9ctSSW$NNjfmh^0`=uPoYlESAUPvRit}10sLWYui9Ffad_`BUaapT1{tt z#K*?Qzyc1xK7R7V3+vOdZZDttjWz?aYu20^pE=EcXAF;bI7Wl?To>@j+5yJ<&LN;} z@7g-Hbi;i9@~2m;F~PF3i?e3ATW(mtwtX+&JU9=ph5tj?L-d0PT*eMtQn_xaBk%@( zZqI}opVJ=4!XZB2#Y-&sKfO*mHX!_eH#igPkEq`JQj4UpP;1l9!xGiwbh!t=`u*un ze#$?5&-$tVq8|QzTtFM1P7Vz0nV(ij=)7g3)kQL*hDN9cm z7=Hw46L2K(Ez26+T^td5-%n&){|S}DzQFU6tHH8olEZ@11L6m8C!8?x@H(XP^=F&; zN}D+jzAsfVGy?aX5!KP)dQZ&QpKDj9n`f%UsqS`MN5XbIq#eN=CeFi?_Yb1sly*bE zIT^|!wd?wu$28r7(ww9+!0Y2ggHLBPFNY;N!QKr9t+U$s#O@*CIoY` zv;89BNNJa)T|LkqX(m|&{{)33kq3av@*G*g06$G*>AN}$VMK6 zo^M5Zr?Os>>%;bP2%%k|F2j_h!#}uiDG}Vkt-9}$)69>HhdhzNwjr)UbNkxJ7*Svn zD0$V;Ki1rD;ZVx{tZ^}F$hgzGR;j1#nL1q)tJXxhQkE^9M$pyAdS%t?C9Nc^WRNemqExP%y?h8W9QTNi+H_}ejEpw{ zMtIS3pXGm6lVAu`=cdS;r8w-2_y{wj*5I!>JT%-4*$8!dJ496g2!;&e$l%wd(+>Gx zk5LyQs}vG9#MATWAQ6r)J; zE;p(PHte+)G5>x3r*J~k?f3CI=7SDM!EY|`@6YRJDe%?GuxSw+mm0pf7Rfkm*f|Cz zk(mvFhaTqDYi5@)A&*Kmbokl{y=={VW3GWU$vD-w+%3qUP!o^)$oW>`Vrwc}<0)`> zs7(E}Y94pjZO_gE8fd;egWS4uUWj7o?IBJ7!+!0pE_lQeO*C!!!OmC^MwVy0^>u^S z?#g3tV4t`089d}2! z*zPv;I_Y&p=5(Z1uy=QY6-BO$ryNb%w|ml@?}{u{EBM@gb!UNmg6n{AcZQ@qk8qP& ze6l|G%fL0;JbR&zUwkc8jBct~4vTb9mSL@9;fK>T_YL~15c^bi&8B^PX5vwLettK% z?cwzBA0zthn@)E37DMGXK04npKgf~Lva>%1^Ws~oGpXD*OJOOp$5%l(nex+TvAufq zam0ts)&^y$2DYMGKX^F-xNMDczgSAr(g+@@&gZc#`ukQl9E5KS_ z3Hw>Qc?G-0ZS<{syPC>vgU`yB(|}KE_iU-2kuO*K+GSlHxt1tzVRUq=8646f{7IW3_bg8wMs-N z!CSR+Jh8_3wDS9ci!|^yj_4Q}?fn+pCjnU#t`8bY6509tV1-GQ&pb!*> zo^FLoRaQHF{oci@P|YMXFsCiCE~`RVP`W@|l`#e}C8cSlse(f7L(vkYn8b+BK=4-( zS&qIYNuH>vEt5{v%^;yoJ)0~~{yc^pe(9A9$=(#!$M0BgkukB(W(>p@YyOOu0&X1R z>s$enIv#J6dm{Ums!+k3T~-aYskGK{_SiPGb++qH4K|jGQlT2v5@`ZST|=q&*+0W` zibPghKVz|#%@+KZg@D%#Sct)a3ewPsjl}EozS#y`@FoJ!S8KM#?fhjK85!_~2N5z0 zew0>Yp*B|lRZL70t0h10Pq$~`7kU4{r1g(?2yI+(TAi3FY9}b1!NxMRl9Nid-mbSx zZI2ct`(_xCuv?uD@-R8#W^Yf5Zt3`=(us98Pcr*$=YLJ_C^N(R#|p1?LM`~VycxB~ z35MHh5{@|*(lnr~ON-?FRy728p7^2~lX8NPtIh?5N#b<|59@~~fV%%ib_iSVg1SMN zV9pz4}a>Q@%Jpy2d~Wv|9T1?^AfPQ;P@(2w<-LXZRExBlbmmN&hjA1GnhIY`#q%3A&!{(|TFnLMQkNNaOz@IjLD(C(&)UDSjHIc{Zbv7wSFJx{ z^0`cp=5SIo`JvHP%n?yd9%a;B8pCO}rEE&B{BVzF!Ejr5ih;-3-+bp+0$yE{L~JZz?a4=)AC02%1Li+$Wzz@u&8!> z+bbtWTj+ViIMvFgWb!0FAHkM7w_&(-jh6X@^Aoe^w>zxuydLZ%<)CMIp13U!!5WSz ze9sr|etWyWSc&X@Ft<%RzknZXeRy`?QcnDX7|d247+`aCW&7hfkpr|Nh?QnQgV*tt zi7<+j15snN*@Vd6*t2t~OJ+RkzPCx8(TxAt$y{wDJ=WfVvGp*LPU!rJh&Sx@a?ta& z;Rdqlt?)ng!Q(d^otMIuGtuTteYh0(VbN{-U0rzo67RhZ*ve0DMF9{GF#yp6T-e}O zHG1e#`Q+baW}ogi(toa?0a`)6t=GxB_M31oTBu~3H*U{(Pt!Gl%V=9aSn}OKcTZ|Q zp_&a+?O7Z3Pk6uBDuMF+y#Vi@OH({>0b2u#hp<{xO_w_34WKhjsq6{z!M{@O+NHbKn-lTKjQXk)qbaaGs?i)FCiT7SAf9 z&9aQVtA8GSA|7nvq5iN+#L?Ql0O5QYb&d4wOFhmeine_QWtczijeRu$Qp zq1_fCHvcaoK#T|D)Z>M&`qblcb#+d5gif}vyv|Dh0<2z2109IE} z7lwZTt39a-^cC9S#rNH>yssBk!m9;FZ20+76Dn-ccN8&M<=tCE>lWgQTrXo9cU}m` z^EKL+%7O9Ol`bpIcUZfObk3z8*1H6|>OMjp95YZTjTiCcpU|I-0vqyb&M+apCggj6 z@8+j>8KhUKen!@j{J*C>D4Z>0tDR8+_y^RBO~*%pf;?^vdn0vdP>qKZ#;*Cb%3lvl zuQZ1BLUEDwaSiGz7Cnt=(%Kj~|mn9KVc4CZi&; zZXHA@uq*ImQ6SN_+IuzcJ}rBmvD1vu)Cb@@QzoL@gKxpRwHy-S9ieY?)9*rPy_P7i ze|n;Vete%it5dor@qJhjc1v$vw()otq;@{m*wpGmTu*Tj>Y|Hsr}1=Md4}*0>qC<( zkR#i%{tI*2DskJi#Udr&s=i_~+dg{E z1&FTXH)joHX_MI;?NBA;q?3l)si^%2=s77s+1fgyf5yWtZ?QQV;etUx)9|myOZ6>nt~D zG57p~EAmu?qf_Mm;tO+lZDMhwu`WiF1xAfEPY72QVE2=Q@tI!%G*Q8nnbg^VtVrjC z-fp<0CgOl5@SWPDqv4UWi#p+n@{|er-QK;UeY#;s;w2XR(m{uxLj8&bcb*diXSILx z@hK_0#j=ER_uu_WTt3Fog(s`O=BMt2>({p$U|6c4N$$*&gv)QwF6og7rC+#Takt!; z$V7*AvkeX`duiz6?K?3d!O@mZG?Ll+y7lOvAcZ821kb*a7byZTdUtyZg%ZC@=vi@m zks`6a*SfU0@*QgD{LfSeJQ>=BWy9q|ghxrn%mr2DQ6IZj85{`kD)-7J6c9`sUVqUZXryfDnv z3z)F4dGs|Vrdn}Z9;+2OuO^St9#vsxsU%5uRTD_yX9}j7z8+aD8#IVGvTO*B&$CR2 zc{Hsvneidv@}uji4exQD7fBQl&iB?|2~vd!=zQ%22v^n>*s1r|x+Hq8#xyzW(35$) zwv(jIe)xK6qXe&dc>{0Nvfl2DY+q#JE7I_1bdM2H))tJ>@mX)g29P+zqM|aE>g~5J z<`%m6h;37ms2X?-#V1tI{Sg+Ou1&0eg2!!dkXF)30m8HKJ&*1NG;4C-X#)?j7%6S^(oDr(9Y#JPdwz3As5bq@GJ0s+rje)F;#wryp!iqIR0ZAR{Rz%Ue;IM zf5C>e@4x-y0_;sB)I6rQqiW=7dM1$m=Xlm6?sh|vdpPVj-2PQ-zroNy&0P3Ac>RCI z3qS4i=+QIv?U<;y-U-x@UWdY?K>Z4}Lh^BV!mGq|dW8(ZLkiC^{9zs1AvV0GU76}) zF}`X&qUPJfN&kGl=5La8GB%^U0JeTaSdS`rJM!Fe2Ii^o&!*=2M(l-f7}>j;Yf^Ch zKjMWRE=0dM67r2+a2knoc!SY{hf?pmFp6!%=%w{W!wHL-xY}SV#YC-PkLr1WWxLf# zhuOf!n{n~P{aZ}Hl(5|Pg^vYF^7mO=}=u6<{Cqld<^pJ{FNodRCqo^ z$&_X&!12}{BF)6N%Tkr%x+P_}9k#hIQJ25`aK!W~+jb(^NSd7tUTqouKSGK|n_2R_ zZcg%#%XXf5>;T>x{ih%>8Y>gPK5n*^De-Eb(P2|~ zsK+(Nl2`rMBDHV+>Uw>Xq+jU%C|+$Vk{r}Dv*G9chXm8zg+bgV2E0zAb)5To(sr54 zKdi5Y&ZL4^gkedBM7E>?|BFXl^<&(hqGXw(&X8UY7ie%O57cZFmqq@dBCj{rQnd%L zw9C|AuacilR69Og44uDP6A`h$zHLiY_(4@xdLJ`w%^Im7@dxk4Ng%!;w5dSm`Ix8g zsDHt{d1*NC8<>o-clX+3rc+reLguf^NpYNDfz@`Bta+t?BBJptX)2$kBSmhl9;aO08KoG-da6gH*g1JFNzrIWsTP(3bfM^!h991 zMBKXJFP}5xP{UN>_FPXbGe5rCe{YmhJJJEmOO?B5OZ?<)_Q!icp~T>ngnC=>!}6~$ zT_`8)_Kj<_NtRO_$7Yjlvl?ajrFU4$mXU!=ySm5l;gX?jtiFeS-${Tw6$4I(A#7zZ zOh0b%SWWZyfT{uW)69l@r**btdg#6`SfJ~W+h&Ngb=SaiJrgUBGrZ4V?jCptA}?vk z`U&_Z9HFl>F8j)4z-UE@<|Uk66u!?|aWZU+ZYExi)&ifv_5AbxUM(ytOxJ+<{lm@&_;_o&Q{QrpJRs)uB1ydfx5s!!Qh5-weg-bl8PpJ0ulzU8dT z;ZydM0@F8P-nmtOqYO^I?|Rk3c4*Ymx~#AEt4#0);_-Y_yW#$Q=A47M7PiN(y?dD# z#G2eM8lISyPPE~j#P~{WeMN`(p(Oj$$hM2cyC<+^%yr*O?ihW9WIA<#C$;>r)VFre zk>mF_F0|3_A}LSK+svyK`x(C~oVRpL z&yyETUb|n_ILw>u3)IAIKynAB94$Zh#%CUFRbzOXY4!V*KNGC3V7|XK#@G6w{G@o{ zy0=nrsaja&+f+Hs!|fikD+0Ciz#%SSwT)gmeQVJolku0eRQgZt{o=&{ZmW0YkFtPG z=+?-gbY4{7on)iRmf*EXFH4UKD!=u_F_DiYzhHbZb>*Ri&-E+H;JjFZLFkn9Wi66H z9z(Oca=}PHso-J_b4ya1pS|s?YtfdX%O{LM3v$YgoG82PwP0bSHW_I0$nuEZaoUZk zLMPIs`&jK}x<}(VTnn#;tXWs>`M@*ij5*bOM-7&1IYTSY764k#_do1e$i<-m{||HE`qib3WZ4@mjaLr2 zs&C`-C0@RKk{d!<`0bTyJ&K}sIb(=gnI9$nB3l1bg)d7u@s!GL7|hfZ6n(ievB`W# zkji(ULK_l>Ws{p0QaXBOsp?Ei0Ra4pAtM|dp7tPsvc{mpVr33 zlgWQmRnSzYRUc*&UOu4|0hP4tSHRg!aB?$NJ~*w(Q13qM!v96`)q zydVl<=FZ4PYxGYcqy}YDu?ga|4h*skNQF?$X~*ifBTbdN2?|*)UFo3l&B~~x%MQK)euJ_ ztUowTbynKAobmxQp`xJn*e|`EGvatlRY*_c$IoFTzuOJt;E-cG@a+v3c?B3bL$!p^ zrYd?73Q#%m-4#K#>tO@UR2EMZnfhgA^!vNP8Szi_=|#t0S&cp97kOIW5w}$rPbaSz zJb$VD11o<($|+ycI4GP@M0h0eSGO7yo?;qm1T-6M&)GY2^)&mFjZsuO-8qq3Z}1x@bb0+jFoHzH^4+aZI)g&Cs7L z4&3M6>nbqBAex{T(^n*#4HC&(#T(Ax`;Y>Lx88D*dn*2d%&?vC5>TXKMS<~%^~b{b zi^-OZj;f<2Nvpc@uu3Oln!N5b2P0TU06Kf-uNE9{H-IbWg;{p z_b_g+@MP)z_2k8X=gCCs4_L6vP0Nq??{ks$V&Z3gEAyyMMyvd_X)m3Xvo&XbKwyW@ zX(7OOCLuook z6~1l#D14+C`IAfFWO(d_HR|ARK^h-sNPzv`f#fQXeE3f#K;0*y^D*J}jh2Rj<1YEpmr)z5{ zb-9rL{zWaQ+hF~uZD9G;tC{FuV3352OdF@&l5dq-@ssNSEajhAQJ;|ON@NHd$ii*8 z`l65vs4#93PwE#o579{oxe*Zd36e3{`~Qg zc9Q$Rcw8X7-jxSPeuy5cMDc1S2~D~uIXS&rhS1!Fo z!kU~Z)dF~m3_o}kVsLw%O#Dz)nj}XgHccTfH757^eWF-(jNq)6b~-k;%yv&y^t#)V zZ!61W+)W6m=MBg0K|05qEgpKNtO)+iUY>)y(#JG+MBJ@9QOT(L>L(Z?dH38tmD6rM z4E2xGR&n15I|okkd|gfi>YkxdY)p%-;Sxkl155AVP5su0N$l#2ya~I>-h2^Seqg-3 zx8@Jz_dz_qI5m=(t~FJzWklnV(>pq0rl!qAM11ETrjTPvm2o(oxvPKybof4vZzw%sNlzDcP_ zZ-(>_=fn{bt&VuOkS|M;&JCAWvXB&VLih2p+YB)s^E>st{#dM#L#+9yeIkzdeaIv0 zGoQz4sY0or&8MhO6F--8oBEig)Wyd2%`_wo0ZbJ4SA**v$8(9b{>eRZ1Pc3n2A7g{ z%V*|mCb1Y=Ez4bO4H-5re$5XBJ#v?LX6^;q(nBz5qwB7@f-ClNb)2o4`jVSj4i6vHIdhhNCku-_Ua;Je6}SjpJ# zNs7!a8NJjtev~80Q?}0bu!49h;AcYmd{wA@rHN9pwh#vou*aeC_$!$pd_>eHNNK2K zf-aiYX#!3!6ze%o0LC`f;Cx~&7?%m{!OB420AFnS4WBD=WsvYd@qwgfqvfD1WLN&` zXewYqcri^4%8#g{B@Q_sgg!W-*7||mJ_7t!M70xzZ>OS2zgqLSv_X7!`jYRA_4QL| z>&@WL#Cv&|=P^qkC70@yGtjyvh$@hLJ}f@Gg`_7Q)9B(kARl3+jI*wRq0i6Pa&3i2 zBGHGjV)@C_f#Rn15X2k^Gcx)6&BqKdR#iys&sD!yDS3CX#r%~l?x%^tX*2AN&5MjP z$r9#W7a=+JG$~Tl+n9D%E5$e*~yk*x!wY=A-#NPIj_n0At+)lr0n0nTo z0_;vsn`H~fq-9+xsG>hSJVTeSDSPj;N?~@1f4kj0TP#2-lU}pb|#S@L83&9fAB3?%=R|#&&u)`#$u<70EhcWw-z|4%ztJ zbfSbPj&31l8!qVvG0*qrjRZOwznJ_v%6Lo$&uSodsxyZG zrYq}LrvC1so%885V-;XUF`Be<4Ilm@)z1#31j(?$2OY;hL6UO5jAE3aENP3+oGt?YvyEq|L15&A^V=8LKQ%g3Uh zDnchSfX)hlP41mKabW=6xNEOMk)Wd5z|&Y(K)p2||M6MAp_)E8Gr40-ESz`u_|Yu& zVJgTzy0xdKw-lXtEG*vH&CaB8noq4BxiiDMZFQ^@dbDKOM(ucHHS1S%~hP=O3*!G1(3HY|~?HvU;JG=CeJhFYZ9peb^s;x_gziuyY$f z94%`kAC!EiiQhEXDT@E@3>HE5DNc(@{B)B-wHPLU#DhX6n&HIws527`AE~Te|393_kvWmei7M5Txa}yLdr-> z|JOsua`$XrxA|1+YPV3mbVdXFU~o&%2TPHR0Ck~=Z03yh1H2WxG@3b;n9sKbKko{I zS!9V7nLC0ri@0-lNH@z@R+H$#-R(eO-M5hxmL63!F?fYaUet}Lg6#{;LasY1K5R(M z+)-XbckG(&3re=nZnBlw8G|(&rwt!KOPGG36O!hedb>KsSax} zHgzRXkl*>ulH+u>w7t1_`ecP&R;IH}Mw;%MW<5fLAw{9uYub!0tT6i{^9_$Zq8V-H3R|L7Y0Pm?GAN;4$}xM0TS*ujj2Cg1Feh zqFrr`({|YHJ9xnUG_QOHbEzpcs_5G!tg%MOf`7gY2*AmEV#1r`p*J9p`5M)Pf+0ee zc&3ABbi0IR|4I*`_Ruv^nB1C%s{D6U0=O&ROG+73+k()a-FTBwg_PU9L|4NJpTFJI zmTLhAQ3k!WIY)MJg&Eh#H%AAcVzN6qcCZSh!)BS~hwO_zO5lSCDmR_f6n241Y9v7& z^O8tAjwz@G5#%i?U*og%%55!}p>>BNnFpo*eX!$bz>g2cbPp3(EGXog` zF`}u?*n7h!E*3bX2Z0GU$!LZS`W{R@@-+3L}FB7YwL2WGeJhhLa_qULnyB}JER78T*lL$lO((5 z@CwvcdBx8y%NR}dD8ZG1XDW3W07Ie?b`M;DA>^GIwoiYwKL2Z8rV3x`HM_^v0a>*t ze{2WXxEeRd+?4IGx3eApPz#-iqYM2tpQIm2q?P5&6S~|i27lx6^?S@5HzO-~?ozt! z9d+)5OhHiD98W{uZek%&dkw(#s9kEN@@H?9PJgBB?;ek?ZlzW|?ubXPW{8FtM@Edx zr%fCf@TF{Gh#=`rzSys!vdWbTH3Lt!1YdymhQhJ2H2r$~O)3v$_|?^|6}?=NYjC9% zng$mKLrFmPR#LiUGl>Q6B*wb9BK;S)X;j{vzLoFC%}3vG=oE=ogoq1Pc6~EPY)!Kl ze}O?xBEDh5jLM)9J|r1h4m_EvD^FQTx^n9r=0p$$Y{jI)c>lyTI&=v>44D>H@+iNH_XJ_6c-=z<5h? zKg6cfK^FVCjCengNWi0;Otfafrc$dsEBOTv%e9;4O zu_?$~m6FuEk0N~!IglQZj4N%>!7hg)y>ywaMB;8;<}*2`q2D<5)bRALx9N|w3*pi! zqk-`d)6W#T=i|HZ2tpsrhW(a`qA^1DaknA=>p6T1+r952O4l+0nyG$D$;Z@W&RpcA2uy#Pe}1; zX9|Pr>bj-b;`LI*Qk2u`moTu|w2ZTk323W%k0;1Kf2Sfdq}AL1R(KY~ij z{j!9AUDUfq;Q&-fK6hUWk?l7;A0{AcEZ~QE2?ufn*poxasgOK-G5fauHGtBrR2H99 zHlP4a=R22gu0~V0B+@D1NO*BlT4MKjrX2WwDaFOzT?_PLcqp_w^R&C>32dC6i7Js? zm4u@ET=n@M8qD;(EL>a(KF|>Tw+=w{(7buMxRu^q={N~~p4X!OVPc{3PCs=GIOUxR z11F6QIu`a`bR^4VPq&PyB9nSs{UaS57<-`MaC$ziQ)xPuJ&@6O)N=D{G^-Q$=F0Fy zJ1p?YXr+;vlNwyqURd(%NZG48QRS$i%)X%Bg5(MI zL}!x*(|P_lu1fsV_4=O<9!|WT#CV-+wlGYAvaoD35J&0vgRz2ez=zsIa#PY<0bo)+4zHWEl+jJ zj!h_N^Qg5arD{8YSgMDA{S^;;Uq&aL;q5(-Xed>C#;;Y6~xW!OJC&Gn>?FYfgvA zKeZKSgv@u;OFfi4Nh?2AM3V z-{$E&N9NiTq9gE{{58|~8VJ$s5IXDmDA4w3Bu}gBWiudg#6)@hOfXm)V^@;)u@5Fq zc%UXn!YEqfWG}RA5e=ATXoP5t1e*5fp9hZ6H8@b2r<@p47pyXk#y#k@#k9s*v|OnL zKPP=g(xSyy^;v6y1s~pvHdkk_UpIw1mv@KD3&Xm0TXi*c2i}?4y_peW3dg9$b#r)T z<73~7i(7|l$=#c)3{H>^-auYlLVz94nXIed&XSzpvcg7Ca@9UPxoe4_WnNDbe%|WJ zBNpMesPiA7YMt^wwWS-tt^Ch--lnw;b&D*tUe$5i4O7{MFI&@&OJ>SCYqM104fxP+ z_o}w_Zs0m$CxGoV>z_*5vo(7->c;#cBOVE}2|*{fGuzPGZD#Fsca(xvdDFT;xB_O( zmcy4_2I>C*>M~q)Se3@xr#*{!CD`i+I5bfynR_=E7>9@Ev{1L8@u!DwE?fN$0&g$s zsvrwKHvXZm;pH4>Dba8tnIqI@H3}gB$QRKTB*+C-?q~5%bED}DDID{6P9mo;Ue@gK zdeOF0a7fuv#P5N-B;NhE3~ecg5akmG&8hcS;| z-m@>`-oDM@$ehDuYv?m~OJJ27vL?qORSEB1Po^1s{w(KM`ety0_Mhi68+`a zIQ#zR9qg+7ug#Dix3}O&<9^+t6zUFTruUH^IOZkg6%>8~oqfGBU-IWj#Mh{`CjIZO zfptHj4LEVs_utA6$5L1o6jYd+%eg?o3rw$wLghuQF?GC zo@KogK|Ji1C#T{QiZLN40S$wTl3VQs3#N`h<`o}nOfeXOxC{pk$k{CVkUd&&K8p)O z+9O&1lzlymc_)Nu4c&63&dbcPUCfu!=7}(JFR)>9B_?x6V)@J;JOb1|$+%}Ty8~32 zIf-lo^uPXegG91?e%3YQJCeB-8eJ1>y!1=sVL)C*qewQPuWg&|TkmrehPFH^c1W?n z@_N<8Gfhl0o=h%K!WmEInI>jx!!+H2Rp5^2v`r#;nvBD33mk`|k>PmGWPGaXE}`7( zfEot@?5Q~|_}+*oJ@@8{A6M?fSe^U$=rt%}V!-RKH)gR#S9TJjNHquxl%muE+P(FVEkC@5Fww>?1K*^2CC;O>P*VgPu z!ixzkKx^vm!HvP7?-6br+H(%1T>-%7n}eSQ7KS2BmRE`*2d->PG3Tn><14~3vAutN zULqd%cS?uBi6a$tERX{!-R-7n*Pr&pb0QpmeS30ioI+j2Ua9PHQ`nUkqCp~DA*zXK zU7be}$*kDh-_K=8?+8fe9deh^z|a#*THRQ(<}k?-A(t={McMV3c#;b}oTHavN*?#QDSM_d&+0 z@5ld$YN)*-^RRr%M(jK>?k=n?*2Au50 zu?^uwvA86IU_d_D0TN*MG5MC@c#1%^0P!*|g zhALT<{@&tPrS0KIbZYXDoAiEdT zk`|EY3#4a`Lo2@T_p#X@U78-j}_+*Qj%bxb!%%%1?b)6P&)f zr22co+LhqUX?@fxWl{vku`jOJCNB_8rC;k^8dPh%UQ-Gy_~9Me3Vfwfbgq9@V>#{c zJYzvraTm%6(e|@8&^B%p>aK8+1Kd}e#go;=4m(QgQG{79GK|`8vIH%gKkXnm9v=`K zA0)>bw%;BQ`RF!?2KjLmSa52V(#)6CX-gaV&Rcith8>a)1@d#Bg1#Y98BCAbopNNP zO^076ygTVDe7m0S{K7cH7$)5cFs?MdB2Mz8B)Q)5Y$@c8IG0}(P7zk#Xt z(Ex>*+)6U{>25rE-yy9$o3pgMc0)o@OK=aoshd^(qg_mw@asCsXpz2{uu1xxVdD!r zL8-|vXi-rXk@b(8QdAKw3&VBpw_jo zNqWXMTfM^jlLJZ}7klgfKvw?$f~>?BCl?W)HcU|)Ex+p#8V{Sg>*26C7mlqYG1P2& zjOOHSEfR#mN^WCpyw2ww>pyJ%iREC#$X@&b*H4wn!dTf=wv+`ZmEiVdHG(g9tDXhtlKK(YyH87fEB%> zPe3mUgB0qp4GXkGJA+ISYxvzKf_8jFz*%&(nG3ciQ^bBHYVL-o4)`B@YFbVDZ+uF- z_RE0Gd>67ODE4$^yIB2--2mBn4KI_?d*m1`pWuW#Z#Pfr!8Ewj!|4b`L6|nT6BOA} z${h~seZ!o6gEs8zpzT?#W`gkUcVPfub{z-3yTdYeP3`z+rGpg!WYfuS1CyABk=bG+ z#>Lkz3>G=0hK(E{^Ob>j+huiB9c5}AsiXB4&j7+&y)9jwBy_DNTLp~u)y|9zv*>`M zTRB}M_3)NNO5kT3u9Qj+m^9jsg*~cYVbaz_y?2NgS+cIRxE zVwQ#(0(x6q=4kCu;!xk=Gpyzzc^tNiCh zna%z*g7+CeSvT|Zpl zI6#q)$TOg(_F_dxOZ&d_H`(`$iu!6q1@2j(Q6AeBFbO{igt=u^=|m^X4%T#gRBw-K z5w~G21bncDC+wJ(o*=pF-rb!&a4OzqkJ1q=X}6#s zL4~b|986%&^)lDQ5&ORZ6hFVxDs38%gK=c#oAX!#j$SNVu2um5Zr@@;O-DefZ)O1U4lDJ z1Hpm^cSvw|cXxMp3BlbOc$M=u+55b6-x%-S@%T~jgYK@X{_0z6%{AAYi9n8OR&)t> zDE`SMn5&`YDn9$mKCol_jo#LQj;M*wW~Ou@h8hsQ)}rV;h=b<)sW>D>Z> zR`yeRg(>U@hF`Q`O`~9EP58g%r<*rDf`-$PXxDm2cK%MDJOAD%PKB-kzAP@5k%?L> z1*#H)?(!xDuGq#G;ry_1^eG)XoMkQ}p7E6rc=K!xY0-sT*+rhrk1|V$kVZR7LF(EP z`wJ>OYOwB2H%4aCjb?0J@UBm)@o@8=*2vH>g~6R7{EG+1yT{#d;lE;!)!W}K-J`E2 z<1>uoxyJU*v*)ORyE&!vFD$jO_XV&UAt?LJ*p|!KuUKSCw~lMhn=QBs!omH4_II8& zI;>_06=ET}!^4KB16@c@n3nG%m_J$d9)2W5qYY73K!cEQ)g)TQ+#Hj3np zN=(wteVG$%yll9~7dcv=3MFve8YaV?Dc7A4KcBz4`SqQg)2l*$D}r&B`%x}my=3d% z)2caD0oY`V!{h{irN0a^N~}NZ-XRMgL;y{EZ=s}Iq4Q!vVjXKi06Dyx-0um@Txwad zz0_{TWe=)zFSiqDcs0lF$@lmR%$Pz}u1gU%7@t8(uT+UP`X8a|qGlU@68ZCiNQm6gHUw9Q+t;AO zH(pCFyT=9`HiR#C2c zV_}uaP_*_Wv{WUeOyv|NIQ%26FSc;cmjfDSGhm9@XtM~azgzi|M1(F(6lsW=V^yq% zEVRw=uJ^+6nZ%t5&ya#t_Q9fIL|yk;gcOjspIL0vwEAju1j#ClR1#x*O*~()rljRu z<_z>8vbmjNX}gv)SNj?+0`nht4l2vx4Kdy&&HWe`GORxaK0V+Zz?6$GK2m1DH@02M zr{J-iGY}qKWe<65aI5AKyoaCO=?%`f*7xLq8m=W8#Dg#jaH;udcOb|ejh>y??+Im7 zO=nzHgnzocTMN0r#3YuIzbY~Gn5SQS9JFY>{fMai!p)D;gb$~OaPG*6!@tsa^=rUa zRe=yrmEER?=1Hd1aKu?qBQ@WRgc)$YmR-BF+qlRqz<4xj7`4OEdT;o$JfydYWVgl}os4woB za=S}wt11)9zkul*?2g`(p5I(jr7j@{ z^ZoBib0j>hTKJKWiNkaV`-ax6saaauThzF}zmQY@ZrqftFr4hkmxmC~Z%z@=Agd?Q zAU}InbSJjm=$xz_l{0>D`3}Wgp#YJqMrQS%WZ|UW--?Y!|J~3llsN|kYj9H>s%#8g z;Us8VL{#7tazhSX4}O#MX^MeMwE<<}q0PL~qc2fU6tguAjF|~`YIIFKqLo%) zAG+)r#LFqV)No_z7R&8GP@F0P(~QHHGtrxtJr-jcX>naJG(~Kpu7!fz;NcD{)w7ht ziG^9CsTBi3X5-XFmDhl(85a9gu>s%3K)!fSz1vggd)ia$q1REx)TC8JRPi+}FF`{W zj&pS%;L^(#*@*bRRR$Lh-I;$YZU7s)cX%_ANYDn~mV{zmJ~Q8rjNPbGVD7p=-Cmm- zVt646Z${w2<#sGbQ*NUvViHCQ;k6a|T*_g3c3MpNRk)E|fkC62Gx;F_OTv*1_u0y5 z+u-Z%pWyweemO|_URziB=9W;1X1uTUr`O9Ws>#FlhZG1b1@biGf+IXm#F4{_MOM^|^AwyHTs6uT?2uV3XFW(+Y476P%N9zvos7;-d(0~$ z?5mz7#R(c3Z?Lqb)JD}YUZfA*kDNZl3EHp?yf?pPoVc@e(m0G)-q&_wVXd%nU*|4^ z&5vOWRC%a*!rScLW6eVq%iJu8ON3L87Q88@i=s2ZPCIgmNZXkHP4-o#Q!P?nG{&}O z0Eg7AG>Lt4#yvq~o-CR@&+lgX5+wfx_m%u&ofse2D}x`F%wG<4L+gVNYl?LHt_bEz zCp+$)m3wen3oxY-K&>@NE!%ayQ+yBSJA{K;|ex7Zv-@;5=&iOFJq zhVY|QkF7bmeRff{Pzi6I?lZvg`0|~`bm+aHv7uwS5jzPJE7$Q5UF?BmD;BQE!EMb; z{4}Zh-G4y2i3yy_r|JD#XmSU8G*WjAiJRw`GFCVKQvr;F$+T@5Bj;JR8whw~JD3L4 zbZeD&<&-;(rl*9Wz)VgCJ0#LoS2z)eoh-O(TUA* zPQt&2oCu0M46;S)PrSj_#w2k@>ftQbT^fVHet;@8s;lx~p9ViXBaorm_`1+>YR&o0 zt?Ad3#_f#{(q|}@=1%&>g<4JkgvljTB65!P+ee8Sbih%V4%_zBSTWg5zMFO5r(R6J zP7j(|wQM)5=kSc|Jq}Xg{EFV4LM~wNbp?e-iB5Vh`?2T8blR!%RZv}t2)-}duaC|f zaNbunnfaXWu!{>ZAkObF-hL2~+p9ArCSD0vUlwBf$?V&USA@to7jG*Fbgzx$tS_2D z*Jk#Yp{5db<8qbw75*4FCZ1|#>h!vBpK3-v@*IIfYvR(j%A>ZR=+G&F~ z3-yli>^&hQoRp z@>I?ccp_*&0B|%g?kyntTO2b2LmCi@f$eFIxmG^V{t11x;sCT2GXR_%*89Kg;S5Pga{V(+j5w>Ln)@VAkJO9Ji<@`;Q}`;ywQ^_P&;ST z;A{sWUt^R$YM)X1hJ#RPRZGeuvE{rGda{=!bem8!#M%bH! ziCTPkr^i;1v&U1TvMvJ25ei}TU~Ax8vGrKKl?t|1a{Kaz#z!du1bDz}FGF-rly9j- za4G{|`v-MY?dJ*?i*2*F&1^xJDlRi)Qv4mV11dI^gDp3eGg`j)StX+Qa5H;d_7@NR z%uhSarX7+8l(SF~QjJ_e`)AK|1muVVZGH8If`<9$`R|WrenA3Ho^EF*(`e+yQ>sih zBL|dJH`mviB|K06@BxW(=pVvxVOFk2+%JJ1YQ)-rpaJeuMpSL|JJTbWGT^piJI6qCxtH*b6CIjD}vE zolBy@!~S@M9i!Gl9X6XOrF;~!R_30+vGG~u`JYPBlK>Dh{r!n#L2#$<&iV^)xMSIJ z2$H&9bJGWB38rK}HnEq@6?zIi-=T85poTbGz-&7b|2ZF|lBBm@1ibF7UBdUf%jK^m zYf`A%BE;jUA{?yb{o%2KU#0CEwso7P?tel?@hPh)Hh6CG#9x*ByV>qJ%Z|8;&7k=) zO~8X;0raYcg~PMN^tbK!6=w`Xu9QESa@BdMUg z;Y*?l-vp?kmUsKE@B-}7t_X{(|B0}-+1nv9qJhJYUP-l5c-)zwfVT~*x$Fd}AGrcO zTW;y8wOVw7?|NY#j&AA-HO`nj+?@0$%PU-dQ(_@lw~prTbHF7`&NHryp8K+Y3&8dQ zm&@b$>qCxAO7ZRW7R36V)NM&C1|TcgUxIiN=B$zv7+6@eDvMNtx-?|g2koL_ch`4* zo(*a`exv4{Hg3Cpf8(4?)PW{>DVN!`(a5&;XliT4_m~L5Fr#vj4=c49V?SsSaWk7$ z{suT7*-r$4fKIye3{7BKO-#t3C2*;kCdRA}151{RI6V=#2ne!NYZf)*d&3e^>a|gK zNlN`K21otpZW~I(pA`an$wX*8B`IaB7CRCkc61#9kyZaHNrJI!Rak*>xbfmQVnKiJiEKKyeraKJl!pTU$V=nuc+gd z&`zz-gy=EyN#+=b=KZROnIkbAzuFBj)ht87!WVoOPF0}RctIHSr-}CAqiXi z1s5URU`|Cg4b;lW7-cHi7DReL}PXc=5SrKZjeoK5O)Lh@R5>hEa%uuDT9w;E8TFgEmLIN-8r68cau}4+ zWky7YzhE&uZBv|+>?^)MzO$~J;?M0VGf7j?FN(KJ$F#ADf3zL9fZ#7$jg+)=B2#4$ zn>%y~R9p?|wt9I~#y3V%Dy$f~gu`F&q*naaN!X}+>6OqTy~RMt{5y$cO_ppfMM?^Y z_N{n{C0aW4I@4Gok>u99YJkJ$yU6=|CF_p^)QV*-pDFU{>nw3P)tpg}rdyB0XvVs8yyiH43k>0_ zoN~*+V^Wj#3X3i>DATP-sULE?yI@w8*Hn1O^7WPR#-ELu>^FTY!Grb{RSo1Ok_85_ z)Q>+q945Ah$l{bUGQa5QJ4(3Om9RQk3Xb&iX;wsvZi}PME8MEuq#1fxKZR+jh!E^dfg40NEMy z4G8u)Zy_Zvu{cv>_fx)uTiV8&cq#pUuQW5^J*cf$KS)5Yq&$Vz2!h|~j~X(= z|AFQ*(p&8pO1nt;K&P0qnysOt_!PJuoO4Ryn9<yzogD?}==SvYLGF5&!5519hM(^KyI)EP!nB0@SgWJ_B@1(}`(_P=Tx48+p^dq%P# z%?*3_B?66|jBPaOkP#$p`hA2186aH{JhZjoxTqbYHiCdL9+zjY+?atre(BA#`?BMM zpeoH&U>@hCpY_v9_mrG*z?t0B)6JPzS>9EA`hqs892G|X4$3zT3V%l<`JC+gcoOEWwE9o)b8Qpj z7801o+-SHp-;Fx3#X(F=LetSss>Ykf zY#*hD^lwT`@IapIfSACc*UMotdOKLbl#kshBY%`VdyCF$P*;~#YoorkL!XCv-qF&D*BTVD@{hD;Y4)tayFjhn5HT2svH6!f z5wBC``v6qV!jrLaSWMK@4R36$Yqtp+dDaxJeX2AFC`A8Rlc`1loZtc9z)dCHb_sWX zsSLZz-?&ed>mMM~Tj7-Q^n~6UerD&qcX;kuOOFNnIIZ?HD%I;*#LH5( zJNg3_xG>1XUfpj3-hxYVfcjDwaHF_M(nO7`0rnmBZi3AG^xL-a&pCa)b`goYhAVw8 z+r@l?1}WyHE*mF%I8M|UCrgqjt`8<4jc{E{6vD+)SH+`TYRk|%yC?RyilPax=$b5CS5XDUqH3BqRVzg<;;j>IC3&?M zXQM=)y~tG#k<-9GyN!fhe6(TH0okNBvx<#nrINtM*wox}>WIPCa@AY%4B)>oaNK(f zhxe)6#Kag?r)NyS(WZ`7T-td}C7?g?Tcdt`Rrgj=NieHHl4(0p#5Sjoed z*&a1X0UFUAR;+=teVYyrNCx#P8K8PISw^#=}o|;WL!>fy-Vnr zigt&RHl_0?E+iPUb%xWc{X^6@x0v(6V~RJm&(}7n2>y=W}fORe;Fp7vk6y~PvgMIH8f6KPEb>WSusq4>io8tqYPY7i~t?)dXL zJ+RDCKu1=xkKan-D{Rol^71|$K)%Q}zm;6!P&z@(8)}jcJL~$A#ufWbYB55IPQ&A2 zy$bbh^)E5M5)&3{4GJK|k{>zH>p5Z5980^eZZPdT#rekXk8k-jdPy-B*>CpX(gdM zgB`?V`NP4@mgjSLSdQG>_#&%5BA!vc7Whq?N>+0tZxgh84_mrn#LKsfk1#7lL1gp; zBIAsV6M1%O5&X<@iR>1! zIv&fftU+b49hIz=_Ajy-=lvEA>bq)Ew1bmEHWiOAdiG?+6N1k-QTD;jT*cK1c`?!w z`tV^;o_r;>({SA78eJ0-=@b82Q!%`0aL!k@>gbQ1n;z9}kkR5PGwJXdiLhrY-ocDF@D#`)yR1 z*y|19%af5o9n&iKf7>3SS!faT+nX8LLH)C($b5%7q_QO9iH;u;$dIoxkIq*_)JWk` zjrC(?jyOM9nB#F~@Vh(zv3$OJ^S2D{ChKnn?0R4XB9&h^KaOo!zz=xNikP*Us<8wE z2k<$_Dh_OTdo$>t$|?N92=(?xf7Ij=aPGvmw0^@;u^E10cxXKRjdXB6#WiXAkH<&S z4=9E>{c20n?TV2%ng!Si8a4WL$+h&HRs-#yBUqtLya_n1a)Lv&8lLBW^8P6+NNGF} zyD+X`ybo614<|)#l~|jU6}07cm_@masK z=)jMO(Pmid7PF2&R@m-(_5{h?| zC1vOc4n$4Vd~-1SI_w%EG7_r4T|%R3XlJ$2BlXi+@N+%dPUuniH+`*NyJp!Xv%M-M zDA{MQBxNejZBMdVn%TfT1y&D}2c&e7dj!;gUbE0{$IZ+~nEBy@=G_O{z>Q#Sz4Z`S z-%H${fsCZcV{OK6kTX0dUh+!w*AzK59NA&2!&NelWa*Y0D2BZ^X913zMaUO;C-Vg; z1s;hrJOX`j)F=|MG@T_1Ek^G8GB7)Q)&2=OLU~LiuQ(dJ-)~$h82uz@yaFL4v)(Zq zX~AI6brNaz{tTch&oh>$UnK zo||tzQ|z#4g;8gm@12uzd^GRzj4ZpOU7nvzjjIuSxA6sDk+Cga=htb!^W9H~Dy>`0 z&!KSM?y+?eFyX>6JvvcZI`|U>t;ulqW@*~4dIcPn-ub>-n2g|&o@JB-lrL&(=h?l+ zOVh>EKkNLV0FdXVY+*67p`z5+(^X>#!(vFrD6L!K7Az}W#OdG$7N(l2zjsWczfJ;+ zt7;#`cN;`549Rhwx{>qz#m+Q-QOmrN!tf-e*p`H;i*SM(dk7H5CS+sM_7O=sL4jEdXJyFQLR#`|Z~RBhG+s?_px5BE0*qojmbwA)hEbtNcEi#VPwm4E>608?pzAG+-} ziqYLwi_nGQrS(EvUMHqL8pC#!EaPaN26@mNl6-k1=bh93mV+=KI;{!IeUk5hN#B#gtoc!#sJsP~`tNOUOJ=TtjtHvf#1^Oa^%K%8V&uCWmN(Gh@1rxG^!KEQ^O zLccDBdyPOB?s@}V*?)5)N4!uw1$!V?t3|h4luG5$hx-T$!`wK+>UQnu=1z0cE;}N5 zw{>Nv?da&bvR6WeVuJOhCmO7#8AUcOSNX8bx%pcBn#e~#B+LsIC{8?anpGSx6=HqW zfdoxwO)osOU&C8w!+SEQ@?o;0v%kFWU{ z?#<6gnMTRhW`;m5=Ww3*z7<$GTdT*x(8+-+@7@*PHI&DFZ{_>@JOm}77o~GKJ$RV! z@9aUBmJER1qr?ZeZxssWANQu&_E!XPfNa7LPOi*EHl$Um? zfY8ZFLrUrY!rfDMP#vr(%pq0bQd4}- zvXzMNt?NA7es>77AhZ3x`8=nq*W|t`eA9ABsC(R&bJCwI69I5TA#P&3VwPvYaJ_9) zne%YM(m6_PPjCz}g|Xi>dzOLG-$?AeADWT~IgxcS@6ar3tVd0W3u3l%qO zDm;7A@!GtJs;w>+dLXY2@3`&!1Q&jbU)J4<(QQ4o=|m;6xSHIcHYaz>0u`?vkwSoT zx>AoG9apsD!n7^Xoxg3ziiv&t#SSOy6_d%e&Gvqi$6oMXWT(Zz-+Kwjj%^}NDjQs7 z4656rUmqXVwa1<1mm<`rA{Ky0wZ>@35x2ahsV34AU2*Rz|8-3#(?!_d(p{ujJwn_8 zX%%xlIvA^b?znm2cJ-`!Fm0gQ{*WLo3GA%{<`IoN`{j|WT^GqpQjlCNXcXD!t z@Uc$f@Co&gTmjBu{Im!;*F(jinovtrUKGXOOm`l|(y7!P*TrQ4IL14f;?Dbdhc0J+ z@V3dvvK}@`()oP`F2h99nVM7izH#)DawO!|GYumZTlccF7|uD_8rXdSai@p<3Wl4` zf66A6A11(u9U2fI(rd@21gNxT(e-~p0uPBZk$)^7*3})QvgA5w7hB!k1z3Em&F0~! z%Om8)8Vf0Q$uahV`fWi?nK4$P;oh*jnoUq@Inzu>K6P|UQ9`@h{J4C%m)dcK05ZLu#U;+OiDnc??g>Ztt2@d&K`~z)@xD>GcF-Uc8)<4)K$M6{#vqAUZ#pL-+kXYBSv1@a!Y{_JiQ&!r-it91G_@6Gmx#db6ju- z1t>&B{d&e=TvrTt$>0$;RiJD)nkxk;WPF#+NOytkDwv?xxe81OY7d50ep0{08~$Fs zb<&_M5bv5;mDboJwsJ(uTZl+R{7W(_q$K`y44!Nxb#0CsphGj+%?EG>uMN>P z41z{W_uj!@<-SKps15V%L9W=y)1VFw4F+$1R|-U(*_Zq4aojAKfYW3k;&+CM+oE8m z#2$cIgqQw;FjhS4QjeYVrG(aZ_y^;7_TmN?Au7PmLJja~2mi=SyJ&V=+kf8dme0y~ zuN)x|rL(=O4BgqoYb(aEGnX1QORyZ?$0#Ts9KwB0$dcrqELS~ z&pkaH-#HlyuEaZm!6=@~`0HWqE&732t7*qm@ljl|)6RRrOpdV@r^=^6w_@(iPo*zC z1t7nY8bOYv1H0>L{SiXcv}IXg2?+b1@&1Fq^K_N&x<9z`ImhbZugR`1YZ6%#+pUPg z!wHZD0hkBs{=ajCz?cFy701zogJYbuQ^hU8LhK6YfW~w24J19xf2^ND0|Wm zCJPjUkwo~oRLeN7CK-%8{{zSmGA4;y=S0TwHX8R@ETRu=%fRk9c@uj8&>W#OI zb6l&aS-mr@WVq6uOTDcDsD%01j#C3LLmj#MM%b^rDHraYxOpt2mx`OwuO)jlzoH7z z*?7)1s#>Q(5$zh(+pthwwHjB;pBe$xGkaz2TC)%Rf`6ilk|_*BoP=LAIY8tI*bSv! z(BH`OBa~eH0=NwsSFG(GHxo7|WVh`*j-0iXBT`WIC}gX4StvS2*&O2HNGOw4u43gy z#SGtIw5&Zx%i1f%OMK!2^mes;TT@78*;3$k<2YQ8jt^Wi)`yxUa?$Ou8sVNRbzc>K zn=t1YPd%Wd#TbNxT7N0%A2S@Nbi`V|;ep~}hAMavO2yB7;XI<#01-zKMDm~ILQna+ z=S;#I6xG03`d!Be2_F6xuBuo6JyjCGg(Vas?vukF9xJS8|Ewtbbf7*tWN=4AG#k5i$81k9iinBm`l1yz zhf{?Qm_+*B)PE>r3bu~T!jQ?{;4C-cZ;K3V+1`{#%8MR;hxppLq;&di*sWVtWd z{2Has!+grAAIa!XxCDn%2F9kf>T-Nt?}@E%-Jd!sbsW!Z>J+P0DG#kjQIBG zG8T!{BZE>_jQ9K~7M(Bje)SB^3f7bUprjqUKl>7rcEcuJ%uD8EpdE9nI+KBvl4{od z3!z`3aT|9U`=Gm1w7@0TQZD}jlor)CMdR3&RV_~`t|1T!|HG)xq@8)*gU|2Kh-mfA z`xF`P!FaZSdl`ZsTG~c3Gp5=WSP~y2m=Z%DlC>gsXXboKkxiy)1W4w;+Ue;jlGsNI zC=jRD2Z)b#-{Z#LzYRt5vt1EGc)klks&MZ)aT{PliZL5n$h*JZOuLeUoO-(BHwYfe zh6-LjDJajZeXl>SWs7< zD$cYg#C}8q!`;p@(@~p=r=2S^ zwyyOfRn|OLPQ3ls(h8>A5kXsL0Y@5t1!xMK>0&L(h3d}%(7e#p-#oh38c#IW~|@X7%Y`!=o~cn=C+s>jdd}ZT~>( zwa(U73!SXvi+uqhIIV}NFxl@bjw4scXOCwC9M&+fk2cv$J3%w$fxpuh5{HKqi9s)T zKE*OPa5hnzAT~5p)AQ%2w;rDZNT5}SEGwWeN)}GLp0E>0>Ti#n^J8PhD^4@D3f^Fj zq0QF7&z+RrUeM2AkQAyMJVXU};@|2yo;6H83TrF=V)2*Ivf6kB{!#hsP=s{J_DP4~ zkrZjwO8&y`MV@xC9=L|o)ezZYq=IqF`N_!YwB^G;yr&jLT@$^|0EF;F{3)X+vrG7g zdx;e}KkOk@7qwW0)z#HLPkjV`4~Ib_)zkn-rs$2ksgpATj0f_zbMVuv?SOh4Z?$u0D4+@$+f;)UmkQq4 zMbI(2no|Nbxg(iO6SW&BMl&eJoVGc-TCKVd-mUR->}z#j2dw-XNCqIH|86vZdwMB|$N7Y+x>UD%;?PpRA9E92tC-tV3e+7^u`*}e!+ zy2dAa8U~u6ycIsld-I`dy8(^Ptdut39o*x&8m0I^D1^&YPO?$6=L(j*^&!nyVOu>N zBz7#fy5O3}l@X8BA$yaGheF;K-lvMH4+GeXDjm-F%vYx3>BZtAqS1Zy@Z&jPlZf_z zE01#k$7~{ee6(T#F$UtAI`)dd92I#Q5#7lr_hdp#%?9sI zI0q#TezNYP&->jOtWurs&@_T;VXo$#kB6>WA_=Gcy)*nrc?JnKrtdYLCS(=?<4wEW z-nsi)I_f~0GF5EAu>KX_SEsJ-iK;>RX9?qKlQ1|6fc<$4rh7r`>8C<${gs{rFWhbouE--mgje34Wnd5% z!sS8v@Z$$p@r8#fb0NqPO6U4w>i{i>skS-=(*)hT(()Z%n($*uEr1JGxk1vg_O#?!*gF2)mC8*h(3IvIeQhy4G<$(%eRR~eaKw?5j`Qgp z`VfEx=WKpKC&Da$ramso;Z+#krpVQLmW|^Pgd5yz8;qK`9 zEtn+^0sqe6Q&a;1tl@Z>H8in$eP~3e`l^R6eQ2x8GxJk`{`p{09F4M)`u@Fk4aeutitWZI6aZ#-QR;1QG~f;!@mJ>4I5 z@=efQ=6UfqUs;*-L6D@!& zzHGqN*6|SA3*!>^RJ2&>*EHOzZrUNu&u3!Yr#W@wegAgv;6n3SqXA@Q|xX@Uw_g&U;rIZXlK6}lS4HlB-*P1(2pUC5< zF?Lv9Z+ILQOn>pVerO$w7L+Nf3lww@nU&w70h}6Q<-8)-NRzpV#ZR*)N>sa#>EG!c z!7+5^q~rbBe`V!?22WK#Cn+gCzGt{FR|Q=;OSx*P11c`22rT`zC6}MkExU-Z891rdH275GyTP)>qCD_sXrs;jjUAX== zPG;@_${6CXV3P^sL{Pw?THDngN9h^@=aRbe1`p@vwkC#Vzyol_#Y5JgtRE-NJw18N za1<(%Nw`;%Hb9ssYH`aSsY&1BKaxGGRc|(-6hTkWj@S2toTL1??(pB&O}}@!+L=J^ z8}q!!ZoYT8vRBIabeAz|*2#`0+bl8~eZXGF$zW-j5?2OI0#5n$`l5AZ;lu&H(hG>W zldhKmHmktOdk6oh{Y(tY701LvKF6K!@_S;n7HbHDb9P~DCLDPt&L?|i1+wl&2U`7N z+dh!J4QsXYT}=Nfn&1*>W1IK&PTa#{Bn)dc*L2AVwuE!_amdAcC05vG?{dOy2UAZd z-P0AsL%DlpgKN+?;0N{Dj+RoD7(=$A3au73F5qiCjRAvVZk>uV5WF^JzFdu)xITuw zjT-_wA?`pOav&g$qubH|3mXh>D}2`QRYH2JJ?z<_rfQhjywb)vV94uKdjE;7Puygd z@5rFJU^cBY{lQqJ+TGj{x z2_yV^jir(;uDX_=9L_I!rAEdz<^~!pf^mZx&3=v5&iY7Ls5{W6Z8PEuE;IO_-0H z@a>);rVL=dF4a|n2h~O>h;!DOP0&d+cn+IX9_2Wo(h5g3xSgFe<3?7{wZ6{P!y#sq zeKmSPqFCSmVL7I-kghx2PT`oSSmS-ZggNKC#4)e%Ug*Dh6`n zCh;3AG=;j4==pr*iRMS1o!=5w7U7dTd`C!1B**lX@Jg$xCInoff6X-9Klwp!axi)6 z+Hn}vp4w>I&Uz;f#4)B#11fotUuR*fcD%0FUG-d`R>skQC=>Fp!NFZDcH=A)m1{>z zUZv}66gdZk%Kz?}QP$`50^S97V}*RBx1Z@v9gl*~k8@1Rmuv^bJ{NSq7|+u^WL zOZ=C1+Y`!tcAIW7xWT*%N3d_Z0YyDZjcd4DUC!cMz?L9rP3-$fRx==*o#mwi z=yS(8V4TdsR$ez_SnN3E=&ExpKQyaMKIMWp7RrUHLjQF&LfjHq(?UD|py1gbROQ+w zV#pU_5V2>EDd_qAHmJkLs!-wlZA7+#m%0jDW^X(mi=vc zWLT+NAAb5H+m=ZVsD~w*ezUdI72`Mu9+;pN^87i_N&9*=oLU=Fh#kA@?dfI3`&W$} z0m%T&k@@%=@$Om`=O=f&X7)@<8TFCN5XW@iwYBQz$C>s1lzE@0Tnz@-xH(!|fjm;f=;W4c|Wl zO%yA6VF?t1%ZJv~jifo8vS$-)dHBj{=0*hLnQrbdAf(OzC}IyJS9NrePV#ywNFe7SQ@aOeqqkB)=@Q5 zy51^9_R4wHDRZMT$CeF@EP2&3aPBBOnr(&?S)Lx>WMv1gp?|tdHy@!j8Gy2l)uYew zmx@JqoW?R4!vP9MfcH{I=bF*_n!)NZN11zKXLg$Y!kE!{lQUgG*vPu#;18hqK%*N+ zW8By{Li?t_<;?i>mY&u?Q`78b`q^Z20kcLJ133*jd#qJhvaQ5x`-!^7#n~j(5{Qt;ca622I-0sK3x9I-0#WtQ zkgVA~kaXlR#Ci`sili+!mPU$*HAzQ-zEpnhZ0t3$>T34XPnCFx zE-r8P#d;cT#tF^Df1vLrW!s+n1W#V-H}2yMx&Q6_nn00J;tFwuxmH?E>WaJB<1+(g z0OVaxgQRW-+fqYJR!_bMpH>e%9IMMX1+mpWY}pB$yDKea4-nxv@XX zahf6{F9&C?P?PU|0@#lId>B>!9IT$(V(-mfs7jvpo>|*%+%C8X1=9&KO>b6m_#nOHFhFD0_Lii^uM}X4OYj z=+w3kJ)-gzpr}Pg!)paDI$yCC9&vLwo?V>qjFOskU1F-S5HDd&^2pgtNm*a}C_-mw z2^^|X+g-Z7*y1M{0y59ve4GCf`fGoPQ|>obX<{%9;!ASOk?(cN#&ERZZK2#eFtaqa z@!)ZmHeTMRgkZ;so&s7LX-z>qX!kyL96nycU2BW3`r{Mg!*6UQ|9&C_6@UcMC|GIz z0p24pFgRUU6$|jancKxqFq1JZPUz)a$YBA4#ZW&$f@miw3T>2zds4I9D|+52WrB#6 z%hBhzl(rp0x2u$Y_+lbv%>5jh!%9f4d4V3H`@npNA$kLn*g2)7S=v+!t4!@mYU_ zl0XYNA}4?|qrOFaAaO~p(u@j0#*&P35Rhr_36Dqgb_%un1S+GwVdp$ z@!^T9EdRolCbpJ^Kl>}M7uD*i>1m-iMRwQ8`Tr$$@^K#XZ{Hsi6I?PFKst`LoClu5 zN@O_Tp^hMErS(x*9p(QacCJs5C)Am*Uj!TfVG8aMRKJ?N9)6kn@as*nhRz>fXgi_b zL6uU3`69_APp1e^$I3Ohwvu(05Z(z5BOop?Al$oSq4Ut}RT4Ppvsm2N)p8lc<@&vh zC`qG}9<85(;C<(=;vR=XiuC#zmL-4M@Imh1gF(L^=UA&$v4aNuimjh4ku3U5Qm_-o zx)nZ49jzS;{=l*Fea9#R3Sh-ViR7zLkLqt-+{D2g#@4HuZ$KE3b+!CBk-z%DM=tv5opyJN;PYZ_Y-}z#ZT)b0+I=w zepvES_<&tx{HtIiXe%G8HXl9!dx;hj+&GlfH2LR18&2BLrtA-$GQ<0Ec6 zR_L@bOA~iv_pF?sdt}zS1oSLPmST3mA?=|ekZhWBx1Y3w92u?$II;~KrXr)6W8f&Ccfu-NsaecRyL+1`dKZ6~vdF9sxNyi>+jA5*Kf z;{SvjZpH$*Ax)*JYk7HvZTxa=IbiFh-dom5KWoVWz$>Y!M+0j~X842JS9~ONN$=$C z_>6*AVhY$7$8xUe8(@rrTn(Uf$tfzy_W9cU29ZDPJIGNsQlxs;4r4V$-HcphcHPS! zPvazUrEXDC9&qgEKQ#czTz@Yl^B8O4|5h|=5U$WH(u2cH$KClV?w|$gl9u0heU3~u zx+eRBiHjhm_sEK&O8@#Mt9cL+w`)B{=Xe=8e2hoYQ~9qY5W(vgnW$;5R)au2Oh{Vz zfh%@G)G1rUxIRkOGoiCON)p&8GDB2T@5%}GE*aWv+&+<&!l3VfGmKKKW*990#l-WI z%S6{|pg!3x6d??eq`WzY-yXhAaP!c3b*ScV%%4=ckrA$Xt3jC8w=;L&fwnI$LHYoC z>nDt~wk1KPzkxJOIMA%R*jed4u+?59jrX+6o%+GlYQ9xzWJw_q6qeG&#A?r9?Puwe zsp*xnXR#mp&^#v)b8^OO_j+ALGl5FaufR^=lCJ59NXGQzbrmvizkG@0>j|ns{WRKm z<&mKcytKJWMkU|$iyoWW1I=YuCPK9R=z|;UZ9&43XzZ+GTJ>O39THOJ|5e*t2F2Ai zZKDu^1Pu_}5=bBfcbNf_;4Z-#+}#BR0?TdPbT%Wh2I%y}mU1s#%MW;}4hmUliRHg0tovPCGOUCs997=7F&)ouf8Q{a)Ys z_0nc*7I;2R^nHUX(%JQD6QPtG_DCtTMMYNa^As?EU<&hy-I(upuF9JE18 z*^<=rIT-M}69bC~&z@h%UpV|8F<1B%gf9mQhxb+}4l1%xhwfhDVnuESllJ2IQeI&2 ziVWm^J8e*S8dHxUGStB7=19E>4a#(_vC!L}6TO%y(rbWX+JDZ%2+MpisWj%lo2fF} z8}oN*x}|Scdve{wTr;7duGYaY3TjdU(f=I|-`X8gX1n(1&f+N{DsU18eGvj?tAqaz z*Q!WW&tg7c-DahFu9gm^MsVTL7mt3IhTIB3^_mJs^Tq5+0C18r^PwDj55OEzKFOECK4zScGe zb83sfqFQ^{zFi+!l|QGn!T_;Ck(QnIsw^)5DNuuKh;&eNmc4oHdFHGq%nC!>_L*TN>jy-qm0-*1l%-xL8dI{A zV3&wPj>mq))mtl%oOco`4neWHG>#r-WZdVj0R#ydR_Zsv$-UOjGC^zt9$P?<(i!W` zew9GokN(lZdo5aw#l;Yfc1?qY4O_gDC*y9BNh?KUF)Fm3aNa7PTqn3qXQ-QP!>bHR3@>;a=r5bNe&qO! zbw@3?>D*N{$Nfj!ia4dJ$n>RaReu|$6`U;eJeMMx;L;&D+55KC^KM%U*b_`>wUk3g zd{LPeUt%8gIiJmx9~AYOoy|ltM~VrbI?(Z~sD18gSmdS>tu6Ic2DW?pBqB=fefVxE z432Zi`XedfXP$x{_#Snq<$)yPW4q<8Iq+3=j|lGKRIn3zE_)As$D=ABUzmn!YQuo%3$SGyvjM2j1d z(Eu3P$J-^PPtj*S&lk0F$RYl%QPBbZKaA_AaR}nbN}Yh$p|P>ao>qgb$FY>z+FAw% zn8ettF5L#~$ANrnRg+D6mID{8ETLgZ@uE@$yQjp95Ca9}Xno($4ufl^h=QOsv&UJg zQ?XuRHbwmMm#9Uu(+r`ftD z&`cz)S`BdnaZoJgsJMrdW=@NbNGJ-K$2lc*RF~(cfSFVzKe@xaXT>?0D82{CDjX3@ zeyZglS`u5o(ncAM`r7;Edr~n%!FbqW;E}+w#^!47ml#aT<9o}+W2+*;Id&WFS#^ER z+9&zp%7Q75+(9MksxDG1<1mR_tQc4&sdqxwz#H`0X=Oz5?sGj?LbK0_ z_%$OB%itZ=G6s}kL(rhr@ZyubQFKl6c|vGJeCZF!LPA?~n^_+cWqQC*3g3{3xCkjl zWtSTak#+dnt`N2y&e1d9N>eMO~%VJPD!M;kD-IWUf~f(=Z0?vj!e*cXa->Uv-TZ>X|UR<$Ad9 zi!PqNfL0#sJ{GU=O1AZUJE`nF8#)9nACw&9ZcXj+_#voPb%Q<3tqp!!K|{ST0Y;6 zXt1X_h?JKIrQvgh3o4Z%X0jJuY))CrmfU7Fo!ADO)c+CdYsJO&T#fAS^J3w_23vi^ z3Gf$}G~}k9c4%vZ>p9#qSm_m`>c$oOlLw%Qql!60#rUF)^RaAn&NxcOD^A!zh!i&M zOU}agA-k}sXn#yBA^3uWho^Fe^+^cdqr~At;~~NXEd5)EskIYBymwj<_dtASeHg{` zWe?R@i8_%>l?gs9Y%D3pLB9mZ*x2m;9!&0wku!RAoHd)LP4N-f(d~;%oR-$aVegG) zEho(crzV5nbfHKt4wI&BSiVfHa9!M5icP$;nr-J3oO*QBoB{LX$lLJ4&Jh@KxdTPp zeagT)@*#98UkzM=zxckHjAg})I8T*g`6fL_7OwxEoj+Dx^p*X|HQ=I?Y9o%gy+QZ#;WC$p=yHB+J zm+CYUZUEJ-czVP$;Pv>&`{;v>aT}fKb#( zq9$LOJ;+e;;4Zl`arK#xw7o^PHDEwntL%&KjFPQsw^AM^rg+5;9*a}YH+^8d=uEYx z(|vcN-tDU1lNwkn9DY3}r&^;+%~sG=YH{oOaWBf?Yx}Q2(XzdF1HkV;zLdne)B!Je zU%Yq$CEW)N?>SJ?5^qC|3MF8pshucdqhgd)_|nv3qcQJMQWY>SpELG61)7mc9H42p#U&7It((zxL-7<2O5}$MyjWEMdrMr5@4Or=IJxJ< zjb$pT9_t_e#t$tT%L4z9v}>Ha$8PqBtUS}(Q3yS))4YY}I6Y94RB;EJ&RlqShbnzo z`cxlI_2bI^wNlNFKjVNbn@^XSo~Gv}TGWkrua5k;Y=Qr_a`6{WQxG3-@(rSx0-N#nixM zNbuVoO(q}eKK7H&eRSTs2koY5P5gYEIkQ0|iu~dPet%;s3%*TJ$+frkeyB7X(tjI% zHYfNf(Bxe{HSYVvl?}Df&XptrcRxrv#{4>=wC8#8sQ|eijjp;@IRkZb&h<}|*=lX+It19) zMOMD}fSehsGIZVc#-XU=gaJ#mOwnMIF{5+xVrvL97x<0ToUP_S^5qe z!|C?9=$Pd#G0tPW{V9T?d) z>8_>5sYYC)A)AHYPL`KDlo#Q&E~M1H2R61Wq2?yKnMM@Ic`EaI5rze@StGhvCeEw(CpqV!Y3%b47zgKytE&tOT?vwiD4gCK& zn*aAx&IQ3+9n3EtUBO|i#F^k;QUjWZ+u_KHC@N}0p%I)1Yv9`Y#**D`V9}fvRhiQ< zIs1pY$6}J`Id`U{OcLq$r-$5$i+MbMJu@51UIiFosTa+3bNs4h!7>qh?R_e>3~-R? zVrYBu4zfAGm7WNotDo;;vUwKxs_@2@u$gqCW=&H&+gz`!wmYuuT~srb=E=OfHC3^} z3SH9H&^^}7xx04>*x+8W`;4lp`|lbLc4#6kN!WxQzU7r2V8Fx-vmLbcRydT>*0s3~ zwd!S|NGDpwz3;%rQ))Zf{L%j=TH4W1(0pM%W^wXp)eCpQ)eK=a=>eDvRl|uTiLV;` zrL7;}-1lxT%cGo7ls>sk(yjU)W*;BdOwTc!Bh<*#i-&BkZRImuY4w5&rGnDkniFd6 zKhvb|b&~Ajn;JCrWm-;z%T~alRm>}=_kqg%{QmHToK6Yh4kY)jXew6laQO6DkoFAV zO_C2C{i=7uJ(NsrEpOKbIc|@m63GOjSvK}eHeBdo=5U zcv~pVfJhFLM3Ua?W*q_?CO^=tJI3@I09xo%(%R|%W->IwbNY$ zMopK*0j!Z~ZI6MktPaT5#*6T^*gvjN;iBh<1SB23g=BTL{k6+ zPW*uUDVR&^i2>Kp%O=oZ+LAMC?jDR9u~+wkP{S`h_Wt;e%o6u?M?FM@1#5sCL$2R> zN7S*^S>BY+R2-Sq=53X~K-GRbS`CPQ)`+wG z#C9PCnod=zs$08hs9i6=dASK~+8yzY$%jW!6QTsXt&2(v)f8Wa`A*F4@j%P6*Y0Td z8CA5?+)^h0A~3G$N2hK6(B|ldw_2gMeN#B8bW>Z2i_dWGaEhVY9b1XecR(&XlJHJEy7dw4Vi{rwmF;8DAqh9p5sT^GEJ0_{@cVu z5AcZHpN|hLrLVMe0A!lyIN34Ds4E^xePER6GM#(vuc{a;3oeKwh3Qbl8~QzWl7ECj z8Fv|_h+=25Jd%YrftwdI$ zp&-hZsYGH*FlHD$oQ9=m8QV2FdV+s;6 zoUFU%L%~G*GYuuzxCMFzMK}Ampt*q+@1q2|s2CN`)qMRH{F*HrArqdy*Tu zPs1QwSc|o+ow(U`wA+i>vv%TS+%$eTHB}e-eL@+Ek?%{>4zJQV=JkWh2@Yjq z%E)cs3wXMvplmn?@z(E&t>rqJ|2D@{!pzZl0&6)ZmvWC1Ze%5>w4?ZEBedtz<`E(b z0vzBZ*Rp$FQ#^*k3rjy-Ktz=xL5RXfT?bttkH`JWf=Y<+z!F#eFT-Mw*!8Ge=9_Kb zZ8aV*y&Tcr5=$#+JA{#~=*QJ{rbcT?g4TrQOdaPD|HlWHmC<*l4s^9xZn{N z+Cs@_sVWuGnBB}ZdoKbvr+BM3CNfmB?y_TL-vz{vUzXpB_)Id4c52#s(JoF>GbEP? zYxV`s64~7AN}r}2q-DNuI3m7=M&ft}vTrz!u0}6M=r*w}YQdk>Z2Pev$-p5Aa3q#1 zX#m30?r)F!6ZDtHGrGJxrw80y+->>rv;JGapfU(hWHa+P==us=E@5Ty7&MGg^x=T- zan)-RQO0Q%Xp?ZB<%VXuJ^Qy3WgR5d=4=48BeOIs;a|KZT|?F-)a6zFlJ5_3m|XDt z_(Dm_V0c18;$*7M_0wp!#Kxw1-Di40w3L1pMfe{%DsF^#`=nYEkcirXtc1k{LMaF= z#!**)mYKNxzBb z4MkNaxt%udh8o8rq1Bvcr4$ZLxbw8#e)L-3h{oBO1R`-C%&@@MI|LRQsWC@Fu#V;F zKDA%b1nNR{zYQc+ZZixxO8_ExMO-?bBRfQ8HWwk8f=dcCppTm-{c6IVGg*oY6KftX z!}HcVegH6(CTh)RC}h(&C0tjm`}%#>$a$86JlQ>?mn!Gc7@tJWqgzk%D&+u{;qlAq-Gzt_0R25WBMSzO8pd)X!7Xd-AZy58U&a@+ zPZ1AOp$%#z4uvX0dND3W-*N~i2(WVA5YxYfgYEuDvJ!g>hJ5a@1tCs z>BIV*g_F(-(yBV=gPgQr=w7@t+)v;&A^mRJ)8P6I{NDC(OO%9Ws1n{0{dE6yG}nEX zW~UzXI7<02x&tva^sY`dY$ooao9-o{Q*DXP>Sw<>U4b{Ib<4fl7iRCF zQ@`zu<0t&`k`sB+>NP&H3YQaA(FXNFe9l9^1leSsX_ShD@yq)&hkmT`b44uTl-=~lCRM<%vZ9kmJ`1wT_Z$w$T~@v$6$|p!hmaQRy6TQo z>f)vdPC~}5yzbTr@sl*iaNS*7t!>2+N7dK0>q_kELlJlh6PfjxLNy^@T$R(fnU-I< zDt&b+1Iu66|NLt}w_iGt4Sd5m%PAhuw6?+1h$~H?NG^V9b~bz<7xpJhx9<035s=3iy}%*oS3-Sc z&a41735lfL9-G91^Di!ngw5s+_M^@Uj$!Z-KBa48IFA!4bGa>(=dAUnx36EUJyDX& zd{^J18D*CId^_D#;l$mcd;$p~``(1-f|3IORxd1Jlk)t?0=>i|dchvKY1Z_7WBR^F zPhTx}{?eGzE_CxJO#`!4|NCgNet6Au&d_q3-c^vtIAik7k&8RuFMcrxdJ76~1Ud%t zW~Que#?nCfkV?{t-d*Jr@tqL6-`b+f(ke3>5DCF-;d zvycwU_61I#{DrtosvnI+Sh3b>;`xHY*d*$~(KV2_Y%B>8?r`j$#tz0Fa}_bAY*Yz! z;)c4-H#+g0u9hj^W-i3F7%`(!%cT=l=~ePx6TYz;SuCtIJ-Bd6Di`JXoshw{noF{5 zZ^x2AaqFOEDHGVX*Nc=dB;h6DKqf}NWo_7MQGqjN){cq9HTZk9vOA#UFcUW^ZeSsW z@?@#SeeQULigv~>F>#F6rc9mB+Ql#%5>^ZT(5I-7Vc#wi#9WE@*QdpNVfN-i zynGt&Ed`>IsCjIn*2;|L*Ol<|4zj5~3i5*O`54e+#|zYLvJjV?t%DB zJBbrZi#<{C6-Ksge3Q@dlgFNIx&2V`5T3}I9#!ZR?s_HGa+D5rRL>G5Zma2Vrn`hq zH_Omqyh^+7o$O33EpBz$OBOv4ON3qfBIr=q@5K?>k&5vJMP@gZxeZ@RO4lta+H=o8 za91F7pYE*--HJ+uwO|29qK_B@mPMgR`;)pw<5m+IZ*1swAE$hxZuoP`jIFdoIRFmgN+px*Hqk)I#h4J=^U@zc?o%d0VMJFYe3NSF(7oq}R+zgHf+Q}Fd;3UU%2o80(%e8=Q_ax!4sPWGd6Q|#<^kp!l*8__ohypxx z9>Tqw5Bs4)(hJYA{pxm_h)mkm6?p7&X$@qFi1eoYq?9L-3J7kb!7VeBei#yf9OLv~ z+29~Dn+vd+b^c^hd7lG##~AddR4?RxW_U!{mqCIL)(EY57aPvEIj(2plvuX&Ygzlc z^Icw?17;4cd`a-LSk}H{8*PfgxsJf7Gw+q1o)0|RuZw#X{7N^&ey>vD7EAD1H#Oi& z8(Nmg{ysjoqvY{mQ0n@r3ricezh$cc{6-1UH4MN8TQE0Fm{GR6`LL~~4u6=$Q6tQf{KYl%+>osB6a9hwXo?A@LDDr8v8l4@3&@# zWQUTe-ET*#HG`H6&T6?6ESogC(x8nu2Ok6A@y>E|NlHEsbhAMMj_i|AJsI|Te)Y0k zTivLl8|sB&H7C|JlV-SIYO^Ns{e*Y`1pelZniG0AlYfAQ^L6}TLH?Vo8BG!;q;Ut8 z0_Z>G-+dbUI#?!oSLsNn0-wUg@!0aFj}7?HEFH^!+&nkKL&?ViRR51eWwN6x=d)&f zi}?Bb_(mEu#vP5^8f-MH{feRKi0+)5gQEVAQhFz@6}j&#JLR(Evl$_g1lhZz{n?EP7*CfJY4+06vYqas(2VoTrp5E1b3|%wJBuOADsqE z=1o4x;u3RJ7zYLoP0VpEQ=2?;dZOE#%H|AMQPR#ymUsKpfcaPs8@ws4tt;K^$R_!~ zB-U?~r0oecj$ypOyaIjo16!AEgq{hkRFA&uC~OH1tvnCNJCnIWRVGYhrqjM*heb=V z1U;P?%@FkqX@VJ`kE%Vu2GUK#^-IGheyhO%$&5LOgUUgBx0bYn&2Kf}@u9!z3}kZQ z=5u*VwmD8iB-h|T;T)3Gb3-xRdG^+BXlvy`{_Y-}eruQAgw`TPr#Tx_eXrv^a!@=; z5PpOj)78bab!wFCYyfjErCN4nxRF*Y$q$X^Vjd<@O-VS1)s_`;(m> zNve7EAEl{nm-Bi#n_4KZx{75H|L*#Z*Rms^`#;*PG0JEvjwCxJ80}W{l0#W+B}Kxx zmo9Fh$;ZRi2AL6?NEA~pLJFgTimJHLzhqt%c{FL7@f;A3l)rt?dIZtD10r5+EF`G# z84+UClzi{or!<_DI3R0EbYGNQncw961JsyL<6g(Ne5#q5wEu{x~4!Dpg5vfyS{niMh_+i4MhUD#eFD=SC~f( z)(oTE0aQKCp%ub`J||DEoM;THJQz=Ty#lN+Fl)U+`f!&CE|fZFyoo{-1ar_x1m9}9b-iQn7j=g z&MW4K=>}bZ?<#$|b>woD@f1O#Z)iL$E&A6ssr!ync-j8#$oRv3@mcq>*RO5j&s{;b zAGf(xkWgt1h{R#u8QL{{NR)nco^%DIU0b_^vYGn}_Y8`@cA)hdhVB3j*@`i)Llmq}g#`Ak>*ZWa}@^psG_D(kf?%xb_PWjOg)gS@*u|<2gpZ4IzB7^0oyC)<-hj?N8;53<$mj8}2r9ag+h`sF zDTAs1OXt)sj_66~K#*};_2VL9x!98Vn)Ft2`vCTXsKCW2^%pPttarWH5wDWR< zdcKGeV~uqCs+#=)^IT(oLFtl7uRZx`tZ13M#??a0oRuieiK_L*FXfprs4yM2IJ*ee zj2=*yPLxlbQR;yN81kuK<;_*Whuy)K3+=zy6$T4rc7OvU&{y%FqqhW(ZpZe^DSP33 zl9ZkRKHfM66|nLJx^M7MDonmgQf)cNj3-et2_ab27&EZXf-gfC2f^w=CAI5M$&`~3 z)vU*Dd`z+3No%k)^JeNSr2G6)4)y6`QBhOWApzpRZ8!OgY>9r1zi~pi%Lb>f5 z8c}@+?E&k{867JwKj8d+JkPUFaiXCmiDaVXbz3_{E-?vzAn*Nlr}SMDz$?=nCGO+| z-=cZr6GDiiza>~t>xDrtGG&N+{Pc119SP^7*36dgwW~Pk(!2Fg21oaf&&69FG`dv% z`f4T*&dF!{{qFa$#fP?NHGFJQi&!Uv(_DD=yyq9s&^F;x)xxPl#TTevh4U_=z=M_p zn`P#A+NMC21PAE8>8pXrNBr?pn8?pZL+iB1k;ga)^naEGx62=X9q<} zMQPI83o?q?2>#Dfl!JvJn+Unmb-f6JH$DRfzarv9Ws-^d2pqnjn!+IJ6~_(|F+6&H z*nMldap&iB+i(_&LQ&phTiGHxaSXSYH|saEs#HN|jgLm_VPU>O<)~p_Z|!39=Z_6G zsDi7}w+7~|%Yf4Fs&x|$*D92Cr@bBv!Nevr zxMSh49eyOVoz3;FtI#CoLIhiHU50L}+{f`@kWIu*R@`&6o2q<#&R|g+ws9Qjs0E9t zDilbbqv&vMIbi*EL40=r8iDh)5)zQDvgh{<5?H}T58vp?D4&1JdI?f;&u{Tj-+e^PAU;Np3w0Zu6VE6ky$fi7!eJlz3vg)YLCI}Vr!FJwEJ&uVY@r@A2>^EY z?g9$S^>M#xATg$(NCV!r{=z&f4I;l(;K+N_C*{5_v2@IuK4EFNn*Tvy?I1^R5`~Gr z-me3f#Hz+z+Kbe@loKO7!WCcG>a~*s`P57yIzbxF;FjYqt40sJbFZ3@ru(DzAf=eor8omRjj5a7QzDLioKI)Vc@R#6@rJh4T@J zGjwM^v4-@oZ&@xz0Kw=kN<~>Z0xxA13T&2_V9mB&zr=;EmmC#Yy+8;+DQ%l&IcqiI zZ7e6PqOVVaFq;embC+ygbZ>Z={Tf%fvBATV5-bf&nO<;=)*JPrYS%B|;yKd4L^Smm z9&0|>8spHuE2=x)f0T1+Rj({jPl~7WWp;0+$Aa#wYs!CG{cE}8&{ZmuUhZ7K@D~0tkyerhN)2bUM((kwb`Xb#rS;5nSF!o zX9NbO#HhCA>FPK`I3B)O>A?2}!UB%1akS$kn@liWnT$HgZNq z!SJtf_gdaIuY!JZ$DE{GGH443aXW=DdXfk+b>F-ED}dK{j4%bGl15*dzw{7zmy|ED z_upO4lhR7zjfanv8f=!&oRu=a_v0?8iMi&4>T@XwDRDs33LG89TW>AR6t1sGwlZrE zR?r;45@X8kUBiFhnMtCQ>ofqvdXAC}oit}hNt_84uFpRXB@_5>d#w`;1Ey>7*4er} z*h}dw(&s`dxlho%vm=lcwY_Ck_ONaQ+9VSC7gRvS8iSv+xnZaBP;WvFN>WZwkKWEW zXwUVCL>lT#r&j%%lvHEK9QAF$-P=KzG8a1b)b-y^rwb3WH2;E?vfXYk_NL0bDl1vT zBO)MwFNQwT+t+tA^$Q&INeBPJ%d!q&C!5?{_#&S?8}dy#Gqb%q`ejXsO)<*9Wz-xr z)ZbZ9o}Ph;d0f;%EXni#l*x8Nw8{>B?nXdvAtV6jW?F@0 zgLZIj_Olfb=m;F$K66)zzuU`vm%DTS?^nfPCRKYgR} zbU%SXlqR1fTmny3Rz4_tL2Xz?rm>wvJS_O%nf-GD3rarNeS@SeNjV2P)MWB!9xBZ1 z$xj3S4A$+ZB^4dQYXs$Em|C-OP+6={Q4p*am~3BGrv=Gl{{ZI?>R8JlX$+z79~9>ao$-wsZi z9(IqyTfcD%nRIzl+T(%~{QOGR6{!>L8JOZx&ahBO;*7oh4Lr7r;2l+KY> zl7Ul`2gFLGWiMHed_@p|VD*#c%_qVjCp=|nquwJY?IXpR zBgwQU@Q`1kWEO$@4oQ;}9|K_<&gJi^+tw%pET43ET=nMKWJ^JQPBF)Smy1ZumaI0t zaVo&aw8@hrC4zA(fH;@6BIyQshxU%kdmQjRBX(1eI_SvZ_U`(Zk5 z=bNR1Nj1@mWRn+9%||e~5?m!aWUlV)D$;TB+L8_$vEVp4*}Pf)`Kdz$X}?yAPqsv! zf0C^=&_}{195>oLDv)*Kifbdd_dTj02D%4=$&q0yRF-g>lt4!tyUCV>?oXQ)azi!I pcA3VMTjV7% ## 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"))