diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 01b56836..4aa77375 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -115,7 +115,7 @@ jobs: runs-on: ubuntu-latest container: image: ubuntu:noble - timeout-minutes: 30 + timeout-minutes: 40 defaults: run: shell: bash diff --git a/README.md b/README.md index df887788..68a0918f 100644 --- a/README.md +++ b/README.md @@ -60,7 +60,7 @@ For more examples, see our [Postman collection](postman/). | ๐Ÿ“ก Subscriptions | **Available** | Stream live data and fault events via SSE | | ๐Ÿ”„ Software Updates | **Available** | Async prepare/execute lifecycle with pluggable backends | | ๐Ÿ”’ Authentication | **Available** | JWT-based RBAC (viewer, operator, configurator, admin) | -| ๐Ÿ“‹ Logs | Planned | Log sources, entries, and configuration | +| ๐Ÿ“‹ Logs | **Available** | Log sources, entries, and configuration | | ๐Ÿ” Entity Lifecycle | Planned | Start, restart, shutdown control | | ๐Ÿ” Modes & Locking | Planned | Target mode control and resource locking | | ๐Ÿ“ Scripts | Planned | Diagnostic script upload and execution | diff --git a/docs/api/rest.rst b/docs/api/rest.rst index 97a55e50..982f0fac 100644 --- a/docs/api/rest.rst +++ b/docs/api/rest.rst @@ -487,6 +487,124 @@ Query and manage faults. - **400:** Invalid status parameter - **503:** Fault manager unavailable +Logs Endpoints +-------------- + +Query and configure the /rosout ring buffer for an entity. Supported entity types: +**components** and **apps**. + +.. note:: + + By default, log entries are sourced from the ``/rosout`` ROS 2 topic. ros2_medkit retains + the 200 most recent entries per node in an in-memory ring buffer (configurable via + ``logs.buffer_size`` in ``gateway_params.yaml``). A ``LogProvider`` plugin can replace the + storage backend or take full ownership of the log pipeline (see plugin development docs). + +``GET /api/v1/components/{id}/logs`` + Query log entries for all nodes in the component namespace (prefix match). + +``GET /api/v1/apps/{id}/logs`` + Query log entries for the specific app node (exact match). + +**Query parameters:** + +.. list-table:: + :header-rows: 1 + :widths: 20 80 + + * - Parameter + - Description + * - ``severity`` + - Minimum severity filter (``debug`` | ``info`` | ``warning`` | ``error`` | ``fatal``). + The stricter of this parameter and the entity's configured ``severity_filter`` is applied. + Without this parameter, the entity's configured ``severity_filter`` (default: ``debug``) + determines the minimum level. Empty or absent = use entity config only. + * - ``context`` + - Substring filter applied to the log entry's logger name (``context.node`` in the response). + Maximum length: 256 characters. Empty or absent = no filter. + +**Response 200:** + +.. code-block:: json + + { + "items": [ + { + "id": "log_42", + "timestamp": "2026-01-15T10:30:00.123456789Z", + "severity": "warning", + "message": "Calibration drift detected", + "context": { + "node": "powertrain/engine/temp_sensor", + "function": "read_sensor", + "file": "temp_sensor.cpp", + "line": 99 + } + } + ] + } + +The ``context.function``, ``context.file``, and ``context.line`` fields are omitted when empty/zero. + +**Severity values** map directly to the ROS 2 log levels: + +.. list-table:: + :header-rows: 1 + :widths: 15 15 70 + + * - Value + - ROS 2 level + - Meaning + * - ``debug`` + - DEBUG (10) + - Fine-grained diagnostic information + * - ``info`` + - INFO (20) + - Normal operational messages + * - ``warning`` + - WARN (30) + - Non-fatal anomalies + * - ``error`` + - ERROR (40) + - Errors that may require attention + * - ``fatal`` + - FATAL (50) + - Critical failures + +``GET /api/v1/components/{id}/logs/configuration`` / ``GET /api/v1/apps/{id}/logs/configuration`` + Return the current log configuration for the entity. + + **Response 200:** + + .. code-block:: json + + { + "severity_filter": "debug", + "max_entries": 100 + } + +``PUT /api/v1/components/{id}/logs/configuration`` / ``PUT /api/v1/apps/{id}/logs/configuration`` + Update the log configuration for the entity. All body fields are optional. + + **Request body:** + + .. code-block:: json + + { + "severity_filter": "warning", + "max_entries": 500 + } + + ``severity_filter`` โ€” minimum severity to return in query results (``debug`` | ``info`` | ``warning`` | + ``error`` | ``fatal``). Entries below this level are excluded from queries. Default: ``debug``. + + ``max_entries`` โ€” maximum number of entries returned per query. Must be between 1 and 10,000 + (inclusive). Default: ``100``. + + **Response 204:** No content. + + - **400:** Invalid ``severity_filter`` or ``max_entries`` value + Bulk Data Endpoints ------------------- diff --git a/docs/requirements/specs/data.rst b/docs/requirements/specs/data.rst index 4bd00e5f..62434d0e 100644 --- a/docs/requirements/specs/data.rst +++ b/docs/requirements/specs/data.rst @@ -3,14 +3,14 @@ Data .. req:: GET /{entity}/data-categories :id: REQ_INTEROP_016 - :status: open + :status: verified :tags: Data The endpoint shall provide metadata about available data categories on the addressed entity. .. req:: GET /{entity}/data-groups :id: REQ_INTEROP_017 - :status: open + :status: verified :tags: Data The endpoint shall provide metadata about defined data or signal groups on the addressed entity. @@ -35,4 +35,3 @@ Data :tags: Data The endpoint shall write a new value to the addressed data item on the entity, if it is writable. - diff --git a/docs/requirements/specs/logs.rst b/docs/requirements/specs/logs.rst index a0a41709..df5ae433 100644 --- a/docs/requirements/specs/logs.rst +++ b/docs/requirements/specs/logs.rst @@ -3,36 +3,22 @@ Logs .. req:: GET /{entity}/logs :id: REQ_INTEROP_061 - :status: open + :status: verified :tags: Logs - The endpoint shall provide an overview of log sources and log configuration for the addressed entity. + The endpoint shall return log entries for the addressed entity, optionally filtered by + severity or context identifier. *(ISO 17978-3 ยง7.21)* -.. req:: GET /{entity}/logs/entries - :id: REQ_INTEROP_062 - :status: open - :tags: Logs - - The endpoint shall return log entries for the addressed entity, optionally in a paged manner. - -.. req:: GET /{entity}/logs/config +.. req:: GET /{entity}/logs/configuration :id: REQ_INTEROP_063 - :status: open + :status: verified :tags: Logs The endpoint shall return the current logging configuration of the addressed entity. -.. req:: PUT /{entity}/logs/config +.. req:: PUT /{entity}/logs/configuration :id: REQ_INTEROP_064 - :status: open + :status: verified :tags: Logs The endpoint shall update the logging configuration of the addressed entity. - -.. req:: DELETE /{entity}/logs/config - :id: REQ_INTEROP_065 - :status: open - :tags: Logs - - The endpoint shall reset the logging configuration of the addressed entity to default settings. - diff --git a/src/ros2_medkit_fault_manager/CMakeLists.txt b/src/ros2_medkit_fault_manager/CMakeLists.txt index 7b7e3329..ac1e7f88 100644 --- a/src/ros2_medkit_fault_manager/CMakeLists.txt +++ b/src/ros2_medkit_fault_manager/CMakeLists.txt @@ -126,24 +126,31 @@ if(BUILD_TESTING) ros2_medkit_clang_tidy() # Unit tests + # Each GTest target that instantiates ROS 2 nodes gets a dedicated ROS_DOMAIN_ID + # so it cannot interfere with launch_testing integration tests that run concurrently + # in the same CTest invocation and launch their own fault_manager_node subprocess. ament_add_gtest(test_fault_manager test/test_fault_manager.cpp) target_link_libraries(test_fault_manager fault_manager_lib) medkit_target_dependencies(test_fault_manager rclcpp ros2_medkit_msgs) + set_tests_properties(test_fault_manager PROPERTIES ENVIRONMENT "ROS_DOMAIN_ID=62") # SQLite storage tests ament_add_gtest(test_sqlite_storage test/test_sqlite_storage.cpp) target_link_libraries(test_sqlite_storage fault_manager_lib) medkit_target_dependencies(test_sqlite_storage rclcpp ros2_medkit_msgs) + set_tests_properties(test_sqlite_storage PROPERTIES ENVIRONMENT "ROS_DOMAIN_ID=63") # Snapshot capture tests ament_add_gtest(test_snapshot_capture test/test_snapshot_capture.cpp) target_link_libraries(test_snapshot_capture fault_manager_lib) medkit_target_dependencies(test_snapshot_capture rclcpp ros2_medkit_msgs) + set_tests_properties(test_snapshot_capture PROPERTIES ENVIRONMENT "ROS_DOMAIN_ID=64") # Rosbag capture tests ament_add_gtest(test_rosbag_capture test/test_rosbag_capture.cpp) target_link_libraries(test_rosbag_capture fault_manager_lib) medkit_target_dependencies(test_rosbag_capture rclcpp ros2_medkit_msgs) + set_tests_properties(test_rosbag_capture PROPERTIES ENVIRONMENT "ROS_DOMAIN_ID=65") # Correlation config parser tests ament_add_gtest(test_correlation_config_parser test/test_correlation_config_parser.cpp) diff --git a/src/ros2_medkit_gateway/CMakeLists.txt b/src/ros2_medkit_gateway/CMakeLists.txt index 9be63260..835d05ec 100644 --- a/src/ros2_medkit_gateway/CMakeLists.txt +++ b/src/ros2_medkit_gateway/CMakeLists.txt @@ -80,6 +80,7 @@ add_library(gateway_lib STATIC src/operation_manager.cpp src/configuration_manager.cpp src/fault_manager.cpp + src/log_manager.cpp src/subscription_manager.cpp # Entity resource model src/models/entity_types.cpp @@ -115,6 +116,7 @@ add_library(gateway_lib STATIC src/http/handlers/operation_handlers.cpp src/http/handlers/config_handlers.cpp src/http/handlers/fault_handlers.cpp + src/http/handlers/log_handlers.cpp src/http/handlers/bulkdata_handlers.cpp src/http/handlers/sse_fault_handler.cpp src/http/handlers/cyclic_subscription_handlers.cpp @@ -442,6 +444,16 @@ if(BUILD_TESTING) ament_add_gtest(test_plugin_manager test/test_plugin_manager.cpp) target_link_libraries(test_plugin_manager gateway_lib) + # Log manager tests + # Dedicated ROS_DOMAIN_ID to prevent cross-talk with concurrent integration tests + ament_add_gtest(test_log_manager test/test_log_manager.cpp) + target_link_libraries(test_log_manager gateway_lib) + set_tests_properties(test_log_manager PROPERTIES ENVIRONMENT "ROS_DOMAIN_ID=66") + + # Log handlers tests + ament_add_gtest(test_log_handlers test/test_log_handlers.cpp) + target_link_libraries(test_log_handlers gateway_lib) + # Apply coverage flags to test targets if(ENABLE_COVERAGE) set(_test_targets @@ -474,6 +486,8 @@ if(BUILD_TESTING) test_health_handlers test_plugin_loader test_plugin_manager + test_log_manager + test_log_handlers ) foreach(_target ${_test_targets}) target_compile_options(${_target} PRIVATE --coverage -O0 -g) diff --git a/src/ros2_medkit_gateway/README.md b/src/ros2_medkit_gateway/README.md index d9c61e27..24cddceb 100644 --- a/src/ros2_medkit_gateway/README.md +++ b/src/ros2_medkit_gateway/README.md @@ -64,6 +64,15 @@ All endpoints are prefixed with `/api/v1` for API versioning. - `POST /api/v1/{entity}/{id}/bulk-data/{category}` - Upload bulk data (components/apps only) - `DELETE /api/v1/{entity}/{id}/bulk-data/{category}/{item_id}` - Delete bulk data (components/apps only) +### Logging Endpoints + +- `GET /api/v1/components/{component_id}/logs` - Query recent log entries for a component (all its nodes, prefix match) +- `GET /api/v1/apps/{app_id}/logs` - Query recent log entries for a specific app node (exact match) +- `GET /api/v1/components/{component_id}/logs/configuration` - Get log configuration for a component +- `GET /api/v1/apps/{app_id}/logs/configuration` - Get log configuration for an app +- `PUT /api/v1/components/{component_id}/logs/configuration` - Update log configuration for a component +- `PUT /api/v1/apps/{app_id}/logs/configuration` - Update log configuration for an app + ### API Reference #### GET /api/v1/areas @@ -966,6 +975,92 @@ ros2 bag info fault_MOTOR_OVERHEAT_1735830000/ | Query via REST | Yes (structured JSON) | Download only | | Default | Enabled | Disabled | +### Logging Endpoints + +The gateway collects `/rosout` messages and exposes them via REST. Each node's log entries are stored in a per-node ring buffer (default: 200 entries, configurable via `logs.buffer_size` in `gateway_params.yaml`). + +**Query parameters for GET /logs:** + +| Parameter | Type | Description | +|-----------|------|-------------| +| `severity` | string | Minimum severity filter: `debug`, `info`, `warning`, `error`, `fatal` | +| `context` | string | Substring filter applied to the logger name | + +#### GET /api/v1/components/{component_id}/logs + +Returns recent log entries for all nodes under the component's namespace (prefix match). Results are capped at `max_entries` (default: 100, configurable per entity via `PUT /logs/configuration`). + +```bash +curl http://localhost:8080/api/v1/components/temp_sensor/logs +curl "http://localhost:8080/api/v1/components/temp_sensor/logs?severity=warning" +``` + +**Response:** + +```json +{ + "items": [ + { + "id": "log_42", + "timestamp": "2026-03-03T12:00:00.000000000Z", + "severity": "warning", + "message": "Temperature exceeded threshold", + "context": { + "node": "powertrain/engine/temp_sensor", + "function": "publish_temperature", + "file": "temp_sensor_node.cpp", + "line": 87 + } + } + ] +} +``` + +#### GET /api/v1/apps/{app_id}/logs + +Same as above but for a single app node (exact logger name match). + +```bash +curl http://localhost:8080/api/v1/apps/temp_sensor/logs +curl "http://localhost:8080/api/v1/apps/temp_sensor/logs?severity=error&context=engine" +``` + +#### GET /api/v1/{entity}/{id}/logs/configuration + +Returns the current log configuration for the entity. + +```bash +curl http://localhost:8080/api/v1/components/temp_sensor/logs/configuration +``` + +**Response:** + +```json +{ + "severity_filter": "debug", + "max_entries": 100 +} +``` + +#### PUT /api/v1/{entity}/{id}/logs/configuration + +Updates the log configuration. Both fields are optional; omitted fields are unchanged. + +```bash +curl -X PUT http://localhost:8080/api/v1/components/temp_sensor/logs/configuration \ + -H "Content-Type: application/json" \ + -d '{"severity_filter": "warning", "max_entries": 50}' +``` + +**Request body:** + +| Field | Type | Description | +|-------|------|-------------| +| `severity_filter` | string | Minimum severity stored/returned: `debug`, `info`, `warning`, `error`, `fatal` | +| `max_entries` | integer > 0 | Maximum entries returned by GET /logs for this entity | + +**Response:** `204 No Content`. + ## Quick Start ### Build diff --git a/src/ros2_medkit_gateway/config/gateway_params.yaml b/src/ros2_medkit_gateway/config/gateway_params.yaml index 642f3e69..f85cb0ff 100644 --- a/src/ros2_medkit_gateway/config/gateway_params.yaml +++ b/src/ros2_medkit_gateway/config/gateway_params.yaml @@ -112,6 +112,15 @@ ros2_medkit_gateway: # Default: 100 max_subscriptions: 100 + # Logging Configuration + logs: + # Ring buffer capacity per node name. + # The gateway retains at most this many /rosout entries per node in memory. + # Oldest entries are dropped when the buffer is full. + # Valid range: 1-100000 (values outside this range are clamped with a warning). + # Default: 200 + buffer_size: 200 + # Discovery Configuration # Controls how ROS 2 graph entities are mapped to SOVD entities discovery: diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/gateway_node.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/gateway_node.hpp index c2ea6e1b..cd431802 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/gateway_node.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/gateway_node.hpp @@ -32,6 +32,7 @@ #include "ros2_medkit_gateway/fault_manager.hpp" #include "ros2_medkit_gateway/http/rate_limiter.hpp" #include "ros2_medkit_gateway/http/rest_server.hpp" +#include "ros2_medkit_gateway/log_manager.hpp" #include "ros2_medkit_gateway/models/thread_safe_entity_cache.hpp" #include "ros2_medkit_gateway/operation_manager.hpp" #include "ros2_medkit_gateway/plugins/plugin_manager.hpp" @@ -89,6 +90,12 @@ class GatewayNode : public rclcpp::Node { */ BulkDataStore * get_bulk_data_store() const; + /** + * @brief Get the LogManager instance + * @return Raw pointer to LogManager (valid for lifetime of GatewayNode) + */ + LogManager * get_log_manager() const; + /** * @brief Get the SubscriptionManager instance * @return Raw pointer to SubscriptionManager (valid for lifetime of GatewayNode) @@ -127,6 +134,7 @@ class GatewayNode : public rclcpp::Node { std::unique_ptr operation_mgr_; std::unique_ptr config_mgr_; std::unique_ptr fault_mgr_; + std::unique_ptr log_mgr_; std::unique_ptr bulk_data_store_; std::unique_ptr subscription_mgr_; // IMPORTANT: plugin_mgr_ BEFORE update_mgr_ - C++ destroys in reverse order, diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/capability_builder.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/capability_builder.hpp index 460c0183..e5d09c29 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/capability_builder.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/capability_builder.hpp @@ -51,7 +51,8 @@ class CapabilityBuilder { CONTAINS, ///< Entity contains other entities (areas->components) RELATED_APPS, ///< Entity has related apps (components only) HOSTS, ///< Entity has host apps (functions/components) - DEPENDS_ON ///< Entity has dependencies (components only) + DEPENDS_ON, ///< Entity has dependencies (components only) + LOGS ///< Entity has communication logs (components and apps) }; /** diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/handlers.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/handlers.hpp index 26c5900c..4da350c3 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/handlers.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/handlers.hpp @@ -35,6 +35,7 @@ #include "ros2_medkit_gateway/http/handlers/fault_handlers.hpp" #include "ros2_medkit_gateway/http/handlers/handler_context.hpp" #include "ros2_medkit_gateway/http/handlers/health_handlers.hpp" +#include "ros2_medkit_gateway/http/handlers/log_handlers.hpp" #include "ros2_medkit_gateway/http/handlers/operation_handlers.hpp" #include "ros2_medkit_gateway/http/handlers/sse_fault_handler.hpp" #include "ros2_medkit_gateway/http/handlers/update_handlers.hpp" diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/log_handlers.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/log_handlers.hpp new file mode 100644 index 00000000..9a968e26 --- /dev/null +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/log_handlers.hpp @@ -0,0 +1,77 @@ +// Copyright 2026 bburda +// +// 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. + +#pragma once + +#include "ros2_medkit_gateway/http/handlers/handler_context.hpp" + +namespace ros2_medkit_gateway { +namespace handlers { + +/** + * @brief Handlers for communication log REST API endpoints. + * + * Provides handlers for: + * - GET /{entity-path}/logs - Query log entries for an entity + * - GET /{entity-path}/logs/configuration - Get log configuration for an entity + * - PUT /{entity-path}/logs/configuration - Update log configuration for an entity + * + * Supported entity types: components, apps. + * + * Log entries are sourced from the /rosout ring buffer by default. + * If a LogProvider plugin is registered, queries are delegated to it. + * + * @par Component vs App semantics + * Components use prefix matching: all nodes whose FQN starts with the + * component namespace are included. Apps use exact FQN matching. + */ +class LogHandlers { + public: + /** + * @brief Construct log handlers with shared context. + * @param ctx The shared handler context + */ + explicit LogHandlers(HandlerContext & ctx) : ctx_(ctx) { + } + + /** + * @brief Handle GET /{entity-path}/logs - query log entries for an entity. + * + * Query parameters: + * severity - Optional minimum severity filter (debug/info/warning/error/fatal). + * Stricter of this and entity config severity_filter is applied. + * context - Optional substring filter applied to the log entry's node name. + */ + void handle_get_logs(const httplib::Request & req, httplib::Response & res); + + /** + * @brief Handle GET /{entity-path}/logs/configuration - get log configuration. + */ + void handle_get_logs_configuration(const httplib::Request & req, httplib::Response & res); + + /** + * @brief Handle PUT /{entity-path}/logs/configuration - update log configuration. + * + * Body (JSON, all fields optional): + * severity_filter - Minimum severity to return in query results (debug/info/warning/error/fatal) + * max_entries - Maximum number of log entries to return per query (> 0) + */ + void handle_put_logs_configuration(const httplib::Request & req, httplib::Response & res); + + private: + HandlerContext & ctx_; +}; + +} // namespace handlers +} // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/rest_server.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/rest_server.hpp index d9eac3e2..89167c49 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/rest_server.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/rest_server.hpp @@ -100,6 +100,7 @@ class RESTServer { std::unique_ptr bulkdata_handlers_; std::unique_ptr cyclic_sub_handlers_; std::unique_ptr update_handlers_; + std::unique_ptr log_handlers_; }; } // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/log_manager.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/log_manager.hpp new file mode 100644 index 00000000..b04d3141 --- /dev/null +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/log_manager.hpp @@ -0,0 +1,157 @@ +// Copyright 2026 bburda +// +// 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. + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "ros2_medkit_gateway/log_types.hpp" +#include "ros2_medkit_gateway/providers/log_provider.hpp" + +namespace ros2_medkit_gateway { + +using json = nlohmann::json; + +class PluginManager; // forward declaration โ€” full include in .cpp + +/** + * @brief Manages /rosout log collection via the default ring-buffer backend. + * + * Subscribes to /rosout, normalizes logger names (strips leading '/'), + * and stores entries per node-name in fixed-size deque ring buffers. + * + * Plugin integration (two modes): + * - **Observer mode** (default): If a LogProvider plugin is registered, get_logs() + * and get_config() delegate to it. on_log_entry() is called on ALL LogProvider + * observers for every /rosout message. Observers returning true suppress ring-buffer + * storage. + * - **Full ingestion** (manages_ingestion() == true): The primary LogProvider owns + * the entire log pipeline. LogManager skips the /rosout subscription and ring buffer + * entirely. All queries and config operations delegate to the plugin. + * + * FQN normalization: + * - entity.fqn from the entity cache has a leading '/' (e.g. "/powertrain/engine/temp_sensor") + * - /rosout msg.name does NOT have a leading '/' (rcl_node_get_logger_name convention) + * - Callers pass raw FQNs from entity.fqn; LogManager strips leading '/' internally. + */ +class LogManager { + public: + /// Default maximum number of entries retained per node in the ring buffer + static constexpr size_t kDefaultBufferSize = 200; + + /** + * @brief Construct LogManager + * + * If the primary LogProvider's manages_ingestion() returns true, the /rosout + * subscription and ring buffer are skipped entirely. Otherwise subscribes to + * /rosout as usual. + * + * @param node ROS 2 node (used for subscription and logging) + * @param plugin_mgr PluginManager for LogProvider lookup (may be nullptr) + * @param max_buffer_size Ring buffer size per node (override for unit testing) + */ + explicit LogManager(rclcpp::Node * node, PluginManager * plugin_mgr = nullptr, + size_t max_buffer_size = kDefaultBufferSize); + + /** + * @brief Query log entries for a set of node FQNs + * + * If a LogProvider plugin is registered, delegates to it. + * Otherwise uses the local ring buffer. + * + * @param node_fqns Node FQNs from entity.fqn (WITH leading '/' โ€” normalized internally) + * @param prefix_match If true, match all buffered nodes whose name starts with the given prefix + * (used for Component queries). If false, exact match (App queries). + * @param min_severity Additional severity filter from query parameter. Empty = no override. + * @param context_filter Substring filter applied to log entry's name (logger name). Empty = no filter. + * @param entity_id Entity ID for config lookup. Empty = use defaults. + * @return JSON array of LogEntry objects sorted by id ascending, capped at entity config max_entries. + */ + tl::expected get_logs(const std::vector & node_fqns, bool prefix_match, + const std::string & min_severity, const std::string & context_filter, + const std::string & entity_id); + + /// Get current log configuration for entity (returns defaults if unconfigured) + tl::expected get_config(const std::string & entity_id) const; + + /** + * @brief Update log configuration for an entity + * @return Empty string on success, error message on validation failure + */ + std::string update_config(const std::string & entity_id, const std::optional & severity_filter, + const std::optional & max_entries); + + // ---- Static utilities (no ROS 2 required โ€” safe in unit tests) ---- + + /// Convert ROS 2 uint8 log level -> SOVD severity string ("debug" for unknown levels) + static std::string level_to_severity(uint8_t level); + + /// Convert SOVD severity string -> ROS 2 uint8 log level (0 for invalid/empty) + static uint8_t severity_to_level(const std::string & severity); + + /// Check if a severity string is valid (one of: debug, info, warning, error, fatal) + static bool is_valid_severity(const std::string & severity); + + /// Format a LogEntry as SOVD JSON (id, timestamp, severity, message, context) + static json entry_to_json(const LogEntry & entry); + + /// Strip leading '/' from a node FQN for ring-buffer key normalization + static std::string normalize_fqn(const std::string & fqn); + + // ---- Test injection (for unit tests โ€” do not use in production code) ---- + + /** + * @brief Inject a log entry directly into the ring buffer (bypasses /rosout subscription) + * + * Used by unit tests to populate the buffer without a live ROS 2 graph. + * In production the buffer is populated exclusively by the /rosout callback. + */ + void inject_entry_for_testing(LogEntry entry); + + private: + void on_rosout(const rcl_interfaces::msg::Log::ConstSharedPtr & msg); + + /// Get the effective LogProvider: plugin if registered, else nullptr (use local buffer) + LogProvider * effective_provider() const; + + rclcpp::Node * node_; + PluginManager * plugin_mgr_; + size_t max_buffer_size_; + + rclcpp::Subscription::SharedPtr rosout_sub_; + + // Ring buffers keyed by normalized node name (no leading '/') + // e.g. "powertrain/engine/temp_sensor" -> deque + std::unordered_map> buffers_; + mutable std::mutex buffers_mutex_; + + // Per-entity configuration keyed by entity_id + std::unordered_map configs_; + mutable std::mutex configs_mutex_; + + // Monotonically increasing entry ID (never resets; starts at 1) + std::atomic next_id_{1}; +}; + +} // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/log_types.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/log_types.hpp new file mode 100644 index 00000000..9397e554 --- /dev/null +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/log_types.hpp @@ -0,0 +1,47 @@ +// Copyright 2026 bburda +// +// 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. + +#pragma once + +#include +#include +#include + +namespace ros2_medkit_gateway { + +/// Per-entity log configuration (query-time result cap and severity filter) +/// +/// Note on max_entries: per the SOVD spec this should be a storage limit; +/// in this implementation it is a query-time result cap (most recent N entries +/// returned). A LogProvider plugin can implement true storage-limit semantics. +struct LogConfig { + std::string severity_filter = "debug"; ///< Minimum severity to include in query results + size_t max_entries = 100; ///< Maximum entries returned per GET /logs request +}; + +/// A single log entry stored in the ring buffer +struct LogEntry { + int64_t id; ///< Monotonically increasing server-assigned ID (starts at 1) + int64_t stamp_sec; ///< Seconds component of log timestamp + uint32_t stamp_nanosec; ///< Nanoseconds component of log timestamp + uint8_t level; ///< ROS 2 log level (10=DEBUG, 20=INFO, 30=WARN, 40=ERROR, 50=FATAL) + std::string name; ///< Logger name from /rosout โ€” FQN WITHOUT leading slash + ///< e.g. "powertrain/engine/temp_sensor" (NOT "/powertrain/...") + std::string msg; ///< Human-readable log message + std::string function; ///< Source function name (may be empty) + std::string file; ///< Source file path (may be empty) + uint32_t line; ///< Source line number (0 if unknown) +}; + +} // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/plugins/plugin_loader.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/plugins/plugin_loader.hpp index 0f732efd..e46cdf61 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/plugins/plugin_loader.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/plugins/plugin_loader.hpp @@ -25,6 +25,7 @@ namespace ros2_medkit_gateway { class UpdateProvider; class IntrospectionProvider; +class LogProvider; /** * @brief Result of loading a gateway plugin. @@ -53,6 +54,10 @@ struct GatewayPluginLoadResult { /// Lifetime tied to plugin - do not use after plugin is destroyed. IntrospectionProvider * introspection_provider = nullptr; + /// Non-owning pointer to LogProvider interface (null if not provided). + /// Lifetime tied to plugin - do not use after plugin is destroyed. + LogProvider * log_provider = nullptr; + private: friend class PluginLoader; void * handle_ = nullptr; // dlopen handle, destroyed after plugin @@ -68,6 +73,7 @@ struct GatewayPluginLoadResult { * Optionally, for provider interface discovery (avoids RTTI across dlopen boundary): * extern "C" UpdateProvider* get_update_provider(GatewayPlugin* plugin); * extern "C" IntrospectionProvider* get_introspection_provider(GatewayPlugin* plugin); + * extern "C" LogProvider* get_log_provider(GatewayPlugin* plugin); * * Path requirements: must be absolute, have .so extension, and resolve to a real file. */ diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/plugins/plugin_manager.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/plugins/plugin_manager.hpp index c764c457..6e0b4347 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/plugins/plugin_manager.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/plugins/plugin_manager.hpp @@ -19,11 +19,13 @@ #include "ros2_medkit_gateway/plugins/plugin_loader.hpp" #include "ros2_medkit_gateway/plugins/plugin_types.hpp" #include "ros2_medkit_gateway/providers/introspection_provider.hpp" +#include "ros2_medkit_gateway/providers/log_provider.hpp" #include "ros2_medkit_gateway/providers/update_provider.hpp" #include #include #include +#include #include #include @@ -115,6 +117,16 @@ class PluginManager { */ std::vector get_introspection_providers() const; + /** + * @brief Get the first plugin implementing LogProvider, or nullptr if none loaded + */ + LogProvider * get_log_provider() const; + + /** + * @brief Get all plugins implementing LogProvider (for observer notifications) + */ + std::vector get_log_observers() const; + // ---- Capability queries (used by discovery handlers) ---- /// Get plugin context (for capability queries from discovery handlers) @@ -134,6 +146,7 @@ class PluginManager { nlohmann::json config; UpdateProvider * update_provider = nullptr; IntrospectionProvider * introspection_provider = nullptr; + LogProvider * log_provider = nullptr; }; /// Disable a plugin after a lifecycle error (nulls providers, resets plugin). @@ -143,7 +156,9 @@ class PluginManager { std::vector plugins_; PluginContext * context_ = nullptr; UpdateProvider * first_update_provider_ = nullptr; + LogProvider * first_log_provider_ = nullptr; bool shutdown_called_ = false; + mutable std::shared_mutex plugins_mutex_; }; } // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/providers/log_provider.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/providers/log_provider.hpp new file mode 100644 index 00000000..4d38e4ee --- /dev/null +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/providers/log_provider.hpp @@ -0,0 +1,138 @@ +// Copyright 2026 bburda +// +// 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. + +#pragma once + +#include "ros2_medkit_gateway/log_types.hpp" + +#include +#include +#include + +namespace ros2_medkit_gateway { + +/** + * @brief Provider interface for log storage backends + * + * Typed provider interface implemented by plugins alongside GatewayPlugin + * via multiple inheritance. When a LogProvider plugin is loaded, LogManager + * delegates all query/config operations to it and stops using the local + * /rosout ring buffer for serving results. + * + * Multiple plugins implementing LogProvider can be loaded; only the first + * registered LogProvider is used for queries (same as UpdateProvider). + * ALL LogProvider plugins receive on_log_entry() calls (observer pattern) - + * unless the primary provider returns true from manages_ingestion(), in which + * case the /rosout subscription is never created and on_log_entry() is never called. + * + * Two modes of operation: + * - **Observer mode** (default, manages_ingestion() == false): LogManager subscribes + * to /rosout and feeds entries to all observers via on_log_entry(). The primary + * provider replaces the query/config backend; the /rosout ring buffer is still + * populated unless on_log_entry() returns true. + * - **Full ingestion** (manages_ingestion() == true): The primary provider owns the + * entire log pipeline - choosing its own source (journald, CloudWatch, custom + * topics), format, and storage. LogManager skips the /rosout subscription and + * ring buffer entirely. + * + * @par Thread safety + * All methods may be called from multiple threads concurrently. + * Implementations must provide their own synchronization. + * + * @par Example use cases + * - OpenTelemetry exporter: implement on_log_entry() to forward to OTLP endpoint + * - Database backend: implement get_logs() to query a SQLite/InfluxDB/etc. store + * - Log aggregator: combine /rosout with external log sources + * - Full ingestion: subscribe to journald/CloudWatch/custom topics directly + * + * @see GatewayPlugin for the base class all plugins must also implement + * @see LogManager for the subsystem that uses this + */ +class LogProvider { + public: + virtual ~LogProvider() = default; + + /** + * @brief Whether this provider fully manages log ingestion + * + * When true, LogManager skips the /rosout subscription and ring buffer entirely. + * The plugin is responsible for sourcing log entries from whatever transport it + * chooses (journald, CloudWatch, custom ROS 2 topics, etc.). + * + * When false (the default), LogManager subscribes to /rosout and populates the + * ring buffer as usual; all LogProvider observers receive on_log_entry() calls. + * + * Only the primary LogProvider's return value is checked (at LogManager construction). + * + * @return true if the plugin owns the entire log pipeline; false for observer mode + */ + virtual bool manages_ingestion() const { + return false; + } + + /** + * @brief Query log entries for a set of node names + * + * @param node_fqns Node FQNs WITHOUT leading slash (e.g. "powertrain/engine/temp_sensor") + * @param prefix_match If true, treat each entry as a namespace prefix (for Component queries). + * If false, match exactly (for App queries). + * @param min_severity Optional additional severity filter ("debug","info","warning","error","fatal"). + * Empty string = no additional filter beyond entity config. + * @param context_filter Optional substring filter applied to the log entry's node/logger name. + * @param entity_id Entity ID for config lookup (determines base severity_filter and max_entries). + * @return LogEntry objects sorted by id ascending, capped at config.max_entries. + * LogManager handles JSON serialization via entry_to_json(). + */ + virtual std::vector get_logs(const std::vector & node_fqns, bool prefix_match, + const std::string & min_severity, const std::string & context_filter, + const std::string & entity_id) = 0; + + /** + * @brief Get the current log configuration for an entity + * @return Entity config (default values if entity was never configured) + */ + virtual LogConfig get_config(const std::string & entity_id) const = 0; + + /** + * @brief Update log configuration for an entity + * @return Empty string on success, error message on validation failure + */ + virtual std::string update_config(const std::string & entity_id, const std::optional & severity_filter, + const std::optional & max_entries) = 0; + + /** + * @brief Called for each /rosout log entry before it is stored in the default ring buffer + * + * All LogProvider plugins receive this call (observer pattern), regardless of + * whether they are the primary query provider. + * + * @note This method is never called when the primary provider's manages_ingestion() + * returns true, because the /rosout subscription is not created in that case. + * + * @param entry The log entry (name field is WITHOUT leading slash) + * @return true to suppress default ring buffer storage; false to allow it (default) + * + * OR-aggregation: if ANY observer returns true, ring buffer storage is suppressed. + * All observers are always called regardless of earlier return values. + * + * Example: An OpenTelemetry plugin forwards to OTLP and returns false (keeps ring buffer). + * A database plugin stores in SQLite, returns true (replaces ring buffer for that entry). + */ + virtual bool on_log_entry(const LogEntry & entry) { + (void)entry; + return false; + } +}; + +} // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/src/gateway_node.cpp b/src/ros2_medkit_gateway/src/gateway_node.cpp index 6a5656ef..7bfb89f0 100644 --- a/src/ros2_medkit_gateway/src/gateway_node.cpp +++ b/src/ros2_medkit_gateway/src/gateway_node.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include using namespace std::chrono_literals; @@ -89,6 +90,10 @@ GatewayNode::GatewayNode() : Node("ros2_medkit_gateway") { declare_parameter("sse.max_clients", 10); // Limit concurrent SSE connections to prevent resource exhaustion declare_parameter("sse.max_subscriptions", 100); // Maximum active cyclic subscriptions across all entities + // Log management parameters + declare_parameter("logs.buffer_size", + 200); // Ring buffer capacity per node; entries exceeding this are dropped (oldest first) + // TLS/HTTPS parameters declare_parameter("server.tls.enabled", false); declare_parameter("server.tls.cert_file", ""); @@ -420,6 +425,18 @@ GatewayNode::GatewayNode() : Node("ros2_medkit_gateway") { RCLCPP_INFO(get_logger(), "Loaded %zu plugin(s)", loaded); } + // Initialize log manager (subscribes to /rosout, delegates to plugin if available) + static constexpr int kMinBufferSize = 1; + static constexpr int kMaxBufferSize = 100000; + auto raw_buffer_size = get_parameter("logs.buffer_size").as_int(); + auto clamped = + std::clamp(raw_buffer_size, static_cast(kMinBufferSize), static_cast(kMaxBufferSize)); + if (clamped != raw_buffer_size) { + RCLCPP_WARN(get_logger(), "logs.buffer_size %" PRId64 " clamped to %" PRId64, raw_buffer_size, clamped); + } + auto log_buffer_size = static_cast(clamped); + log_mgr_ = std::make_unique(this, plugin_mgr_.get(), log_buffer_size); + // Initialize update manager auto updates_enabled = get_parameter("updates.enabled").as_bool(); if (updates_enabled) { @@ -502,6 +519,10 @@ FaultManager * GatewayNode::get_fault_manager() const { return fault_mgr_.get(); } +LogManager * GatewayNode::get_log_manager() const { + return log_mgr_.get(); +} + BulkDataStore * GatewayNode::get_bulk_data_store() const { return bulk_data_store_.get(); } diff --git a/src/ros2_medkit_gateway/src/http/handlers/capability_builder.cpp b/src/ros2_medkit_gateway/src/http/handlers/capability_builder.cpp index 9739961b..c9e10836 100644 --- a/src/ros2_medkit_gateway/src/http/handlers/capability_builder.cpp +++ b/src/ros2_medkit_gateway/src/http/handlers/capability_builder.cpp @@ -41,6 +41,8 @@ std::string CapabilityBuilder::capability_to_name(Capability cap) { return "hosts"; case Capability::DEPENDS_ON: return "depends-on"; + case Capability::LOGS: + return "logs"; default: return "unknown"; } diff --git a/src/ros2_medkit_gateway/src/http/handlers/discovery_handlers.cpp b/src/ros2_medkit_gateway/src/http/handlers/discovery_handlers.cpp index c19163ec..2f0645ea 100644 --- a/src/ros2_medkit_gateway/src/http/handlers/discovery_handlers.cpp +++ b/src/ros2_medkit_gateway/src/http/handlers/discovery_handlers.cpp @@ -489,13 +489,16 @@ void DiscoveryHandlers::handle_get_component(const httplib::Request & req, httpl } using Cap = CapabilityBuilder::Capability; - std::vector caps = {Cap::DATA, Cap::OPERATIONS, Cap::CONFIGURATIONS, - Cap::FAULTS, Cap::SUBCOMPONENTS, Cap::HOSTS}; + std::vector caps = {Cap::DATA, Cap::OPERATIONS, Cap::CONFIGURATIONS, Cap::FAULTS, + Cap::LOGS, Cap::SUBCOMPONENTS, Cap::HOSTS}; if (!comp.depends_on.empty()) { caps.push_back(Cap::DEPENDS_ON); } auto comp_caps = CapabilityBuilder::build_capabilities("components", comp.id, caps); append_plugin_capabilities(comp_caps, "components", comp.id, SovdEntityType::COMPONENT, ctx_.node()); + // Capabilities at root level (SOVD standard) and in x-medkit (vendor extension for tools + // that only read x-medkit). Apps don't duplicate because they have no vendor extensions block. + response["capabilities"] = comp_caps; ext.add("capabilities", comp_caps); response["x-medkit"] = ext.build(); @@ -812,7 +815,7 @@ void DiscoveryHandlers::handle_get_app(const httplib::Request & req, httplib::Re } using Cap = CapabilityBuilder::Capability; - std::vector caps = {Cap::DATA, Cap::OPERATIONS, Cap::CONFIGURATIONS, Cap::FAULTS}; + std::vector caps = {Cap::DATA, Cap::OPERATIONS, Cap::CONFIGURATIONS, Cap::FAULTS, Cap::LOGS}; response["capabilities"] = CapabilityBuilder::build_capabilities("apps", app.id, caps); append_plugin_capabilities(response["capabilities"], "apps", app.id, SovdEntityType::APP, ctx_.node()); diff --git a/src/ros2_medkit_gateway/src/http/handlers/log_handlers.cpp b/src/ros2_medkit_gateway/src/http/handlers/log_handlers.cpp new file mode 100644 index 00000000..be2aaddb --- /dev/null +++ b/src/ros2_medkit_gateway/src/http/handlers/log_handlers.cpp @@ -0,0 +1,202 @@ +// Copyright 2026 bburda +// +// 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 "ros2_medkit_gateway/http/handlers/log_handlers.hpp" + +#include +#include +#include + +#include "ros2_medkit_gateway/gateway_node.hpp" +#include "ros2_medkit_gateway/http/error_codes.hpp" + +namespace ros2_medkit_gateway { +namespace handlers { + +namespace { +using json = nlohmann::json; +} // namespace + +// --------------------------------------------------------------------------- +// handle_get_logs +// --------------------------------------------------------------------------- + +void LogHandlers::handle_get_logs(const httplib::Request & req, httplib::Response & res) { + if (req.matches.size() < 2) { + HandlerContext::send_error(res, 400, ERR_INVALID_REQUEST, "Invalid request"); + return; + } + + const auto entity_id = req.matches[1].str(); + auto entity_opt = ctx_.validate_entity_for_route(req, res, entity_id); + if (!entity_opt) { + return; + } + const auto & entity = *entity_opt; + + auto * log_mgr = ctx_.node()->get_log_manager(); + if (!log_mgr) { + HandlerContext::send_error(res, 503, ERR_SERVICE_UNAVAILABLE, "LogManager not available"); + return; + } + + // Components use prefix matching (all nodes under the component namespace); + // Apps use exact matching (single node FQN). + const bool prefix_match = (entity.type == EntityType::COMPONENT); + + // Optional query parameters + const std::string min_severity = req.get_param_value("severity"); + const std::string context_filter = req.get_param_value("context"); + + if (!min_severity.empty() && !LogManager::is_valid_severity(min_severity)) { + HandlerContext::send_error(res, 400, ERR_INVALID_PARAMETER, + "Invalid severity value: must be one of debug, info, warning, error, fatal"); + return; + } + + static constexpr size_t kMaxContextFilterLen = 256; + if (context_filter.size() > kMaxContextFilterLen) { + HandlerContext::send_error(res, 400, ERR_INVALID_PARAMETER, "context filter exceeds maximum length of 256"); + return; + } + + auto logs = log_mgr->get_logs({entity.fqn}, prefix_match, min_severity, context_filter, entity_id); + if (!logs) { + HandlerContext::send_error(res, 503, ERR_SERVICE_UNAVAILABLE, logs.error()); + return; + } + + json result; + result["items"] = std::move(*logs); + HandlerContext::send_json(res, result); +} + +// --------------------------------------------------------------------------- +// handle_get_logs_configuration +// --------------------------------------------------------------------------- + +void LogHandlers::handle_get_logs_configuration(const httplib::Request & req, httplib::Response & res) { + if (req.matches.size() < 2) { + HandlerContext::send_error(res, 400, ERR_INVALID_REQUEST, "Invalid request"); + return; + } + + const auto entity_id = req.matches[1].str(); + auto entity_opt = ctx_.validate_entity_for_route(req, res, entity_id); + if (!entity_opt) { + return; + } + + auto * log_mgr = ctx_.node()->get_log_manager(); + if (!log_mgr) { + HandlerContext::send_error(res, 503, ERR_SERVICE_UNAVAILABLE, "LogManager not available"); + return; + } + + auto cfg = log_mgr->get_config(entity_id); + if (!cfg) { + HandlerContext::send_error(res, 503, ERR_SERVICE_UNAVAILABLE, cfg.error()); + return; + } + + json result; + result["severity_filter"] = cfg->severity_filter; + result["max_entries"] = cfg->max_entries; + HandlerContext::send_json(res, result); +} + +// --------------------------------------------------------------------------- +// handle_put_logs_configuration +// --------------------------------------------------------------------------- + +void LogHandlers::handle_put_logs_configuration(const httplib::Request & req, httplib::Response & res) { + if (req.matches.size() < 2) { + HandlerContext::send_error(res, 400, ERR_INVALID_REQUEST, "Invalid request"); + return; + } + + const auto entity_id = req.matches[1].str(); + auto entity_opt = ctx_.validate_entity_for_route(req, res, entity_id); + if (!entity_opt) { + return; + } + + auto * log_mgr = ctx_.node()->get_log_manager(); + if (!log_mgr) { + HandlerContext::send_error(res, 503, ERR_SERVICE_UNAVAILABLE, "LogManager not available"); + return; + } + + json body; + try { + body = json::parse(req.body); + } catch (const json::parse_error &) { + HandlerContext::send_error(res, 400, ERR_INVALID_REQUEST, "Invalid JSON in request body"); + return; + } + + std::optional severity_filter; + std::optional max_entries; + + if (body.contains("severity_filter")) { + if (!body["severity_filter"].is_string()) { + HandlerContext::send_error(res, 400, ERR_INVALID_PARAMETER, "severity_filter must be a string"); + return; + } + severity_filter = body["severity_filter"].get(); + } + + static constexpr long long kMaxEntriesCap = 10000; + if (body.contains("max_entries")) { + const auto & me = body["max_entries"]; + if (!me.is_number_integer() && !me.is_number_unsigned()) { + HandlerContext::send_error(res, 400, ERR_INVALID_PARAMETER, "max_entries must be a positive integer"); + return; + } + long long val = 0; + try { + val = me.get(); + } catch (const nlohmann::json::exception &) { + HandlerContext::send_error(res, 400, ERR_INVALID_PARAMETER, "max_entries value out of range"); + return; + } + if (val <= 0) { + HandlerContext::send_error(res, 400, ERR_INVALID_PARAMETER, "max_entries must be greater than 0"); + return; + } + if (val > kMaxEntriesCap) { + HandlerContext::send_error(res, 400, ERR_INVALID_PARAMETER, "max_entries exceeds maximum allowed value of 10000"); + return; + } + max_entries = static_cast(val); + } + + // Warn about unrecognized fields (helps debug camelCase typos like "severityFilter") + for (const auto & [key, _] : body.items()) { + if (key != "severity_filter" && key != "max_entries") { + RCLCPP_DEBUG(HandlerContext::logger(), "PUT /logs/configuration: ignoring unrecognized field '%s'", key.c_str()); + } + } + + const auto err = log_mgr->update_config(entity_id, severity_filter, max_entries); + if (!err.empty()) { + HandlerContext::send_error(res, 400, ERR_INVALID_PARAMETER, err); + return; + } + + res.status = 204; +} + +} // namespace handlers +} // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/src/http/rest_server.cpp b/src/ros2_medkit_gateway/src/http/rest_server.cpp index feb99fb4..44c0ce6c 100644 --- a/src/ros2_medkit_gateway/src/http/rest_server.cpp +++ b/src/ros2_medkit_gateway/src/http/rest_server.cpp @@ -119,6 +119,7 @@ RESTServer::RESTServer(GatewayNode * node, const std::string & host, int port, c operation_handlers_ = std::make_unique(*handler_ctx_); config_handlers_ = std::make_unique(*handler_ctx_); fault_handlers_ = std::make_unique(*handler_ctx_); + log_handlers_ = std::make_unique(*handler_ctx_); auth_handlers_ = std::make_unique(*handler_ctx_); auto max_sse_clients = static_cast(node_->get_parameter("sse.max_clients").as_int()); sse_client_tracker_ = std::make_shared(max_sse_clients); @@ -817,6 +818,43 @@ void RESTServer::setup_routes() { fault_handlers_->handle_clear_all_faults(req, res); }); + // === Communication Log Routes (issue 208) === + + // GET /components/{id}/logs - query log entries for a component (prefix match) + srv->Get((api_path("/components") + R"(/([^/]+)/logs$)"), + [this](const httplib::Request & req, httplib::Response & res) { + log_handlers_->handle_get_logs(req, res); + }); + + // GET /apps/{id}/logs - query log entries for an app (exact match) + srv->Get((api_path("/apps") + R"(/([^/]+)/logs$)"), [this](const httplib::Request & req, httplib::Response & res) { + log_handlers_->handle_get_logs(req, res); + }); + + // GET /components/{id}/logs/configuration - get log configuration for a component + srv->Get((api_path("/components") + R"(/([^/]+)/logs/configuration$)"), + [this](const httplib::Request & req, httplib::Response & res) { + log_handlers_->handle_get_logs_configuration(req, res); + }); + + // GET /apps/{id}/logs/configuration - get log configuration for an app + srv->Get((api_path("/apps") + R"(/([^/]+)/logs/configuration$)"), + [this](const httplib::Request & req, httplib::Response & res) { + log_handlers_->handle_get_logs_configuration(req, res); + }); + + // PUT /components/{id}/logs/configuration - update log configuration for a component + srv->Put((api_path("/components") + R"(/([^/]+)/logs/configuration$)"), + [this](const httplib::Request & req, httplib::Response & res) { + log_handlers_->handle_put_logs_configuration(req, res); + }); + + // PUT /apps/{id}/logs/configuration - update log configuration for an app + srv->Put((api_path("/apps") + R"(/([^/]+)/logs/configuration$)"), + [this](const httplib::Request & req, httplib::Response & res) { + log_handlers_->handle_put_logs_configuration(req, res); + }); + // === Bulk Data Routes (REQ_INTEROP_071-073) === // List bulk-data categories srv->Get((api_path("/apps") + R"(/([^/]+)/bulk-data$)"), diff --git a/src/ros2_medkit_gateway/src/log_manager.cpp b/src/ros2_medkit_gateway/src/log_manager.cpp new file mode 100644 index 00000000..a8698d00 --- /dev/null +++ b/src/ros2_medkit_gateway/src/log_manager.cpp @@ -0,0 +1,368 @@ +// Copyright 2026 bburda +// +// 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 "ros2_medkit_gateway/log_manager.hpp" + +#include +#include +#include +#include + +#include "ros2_medkit_gateway/plugins/plugin_manager.hpp" + +namespace ros2_medkit_gateway { + +namespace { +// Log level aliases matching rcl_interfaces::msg::Log constants +using Log = rcl_interfaces::msg::Log; +} // namespace + +// --------------------------------------------------------------------------- +// Static helpers +// --------------------------------------------------------------------------- + +std::string LogManager::level_to_severity(uint8_t level) { + switch (level) { + case Log::DEBUG: + return "debug"; + case Log::INFO: + return "info"; + case Log::WARN: + return "warning"; + case Log::ERROR: + return "error"; + case Log::FATAL: + return "fatal"; + default: + return "debug"; + } +} + +uint8_t LogManager::severity_to_level(const std::string & severity) { + if (severity == "debug") { + return Log::DEBUG; + } + if (severity == "info") { + return Log::INFO; + } + if (severity == "warning") { + return Log::WARN; + } + if (severity == "error") { + return Log::ERROR; + } + if (severity == "fatal") { + return Log::FATAL; + } + return 0; +} + +bool LogManager::is_valid_severity(const std::string & severity) { + return severity_to_level(severity) != 0; +} + +std::string LogManager::normalize_fqn(const std::string & fqn) { + if (!fqn.empty() && fqn[0] == '/') { + return fqn.substr(1); + } + return fqn; +} + +json LogManager::entry_to_json(const LogEntry & e) { + // Format as ISO 8601 UTC + std::time_t t = static_cast(e.stamp_sec); + std::tm tm_utc{}; + gmtime_r(&t, &tm_utc); + std::ostringstream ts; + ts << std::put_time(&tm_utc, "%Y-%m-%dT%H:%M:%S"); + ts << "." << std::setfill('0') << std::setw(9) << e.stamp_nanosec << "Z"; + + json j; + j["id"] = "log_" + std::to_string(e.id); + j["timestamp"] = ts.str(); + j["severity"] = level_to_severity(e.level); + j["message"] = e.msg; + + json ctx; + ctx["node"] = e.name; + if (!e.function.empty()) { + ctx["function"] = e.function; + } + if (!e.file.empty()) { + ctx["file"] = e.file; + } + if (e.line != 0) { + ctx["line"] = e.line; + } + j["context"] = ctx; + + return j; +} + +// --------------------------------------------------------------------------- +// Constructor +// --------------------------------------------------------------------------- + +LogManager::LogManager(rclcpp::Node * node, PluginManager * plugin_mgr, size_t max_buffer_size) + : node_(node), plugin_mgr_(plugin_mgr), max_buffer_size_(max_buffer_size) { + auto * provider = effective_provider(); + if (provider && provider->manages_ingestion()) { + RCLCPP_INFO(node_->get_logger(), + "LogManager: primary LogProvider manages ingestion - skipping /rosout subscription"); + return; + } + + rosout_sub_ = node_->create_subscription( + "/rosout", rclcpp::QoS(100), [this](const rcl_interfaces::msg::Log::ConstSharedPtr & msg) { + on_rosout(msg); + }); + + RCLCPP_INFO(node_->get_logger(), "LogManager: subscribed to /rosout (buffer_size=%zu)", max_buffer_size_); +} + +// --------------------------------------------------------------------------- +// /rosout callback +// --------------------------------------------------------------------------- + +void LogManager::on_rosout(const rcl_interfaces::msg::Log::ConstSharedPtr & msg) { + LogEntry entry; + entry.id = next_id_.fetch_add(1, std::memory_order_relaxed); + entry.stamp_sec = msg->stamp.sec; + entry.stamp_nanosec = msg->stamp.nanosec; + entry.level = msg->level; + entry.name = msg->name; // already without leading slash per rcl convention + entry.msg = msg->msg; + entry.function = msg->function; + entry.file = msg->file; + entry.line = msg->line; + + // Notify all LogProvider observers โ€” they may forward to OTel, DB, etc. + // Exceptions from plugins are caught to prevent a misbehaving plugin from + // crashing the gateway's ROS 2 subscription callback. + bool suppress_buffer = false; + if (plugin_mgr_) { + for (auto * observer : plugin_mgr_->get_log_observers()) { + try { + if (observer->on_log_entry(entry)) { + suppress_buffer = true; + } + } catch (const std::exception & e) { + RCLCPP_WARN(node_->get_logger(), "LogProvider::on_log_entry threw: %s", e.what()); + } catch (...) { + RCLCPP_WARN(node_->get_logger(), "LogProvider::on_log_entry threw unknown exception"); + } + } + } + + if (!suppress_buffer) { + std::lock_guard lock(buffers_mutex_); + auto & buf = buffers_[entry.name]; + buf.push_back(std::move(entry)); + if (buf.size() > max_buffer_size_) { + buf.pop_front(); + } + } +} + +// --------------------------------------------------------------------------- +// inject_entry_for_testing +// --------------------------------------------------------------------------- + +void LogManager::inject_entry_for_testing(LogEntry entry) { + std::lock_guard lock(buffers_mutex_); + auto & buf = buffers_[entry.name]; + buf.push_back(std::move(entry)); + if (buf.size() > max_buffer_size_) { + buf.pop_front(); + } +} + +// --------------------------------------------------------------------------- +// effective_provider +// --------------------------------------------------------------------------- + +LogProvider * LogManager::effective_provider() const { + if (plugin_mgr_) { + return plugin_mgr_->get_log_provider(); + } + return nullptr; +} + +// --------------------------------------------------------------------------- +// get_logs +// --------------------------------------------------------------------------- + +tl::expected LogManager::get_logs(const std::vector & node_fqns, bool prefix_match, + const std::string & min_severity, + const std::string & context_filter, + const std::string & entity_id) { + // Delegate to plugin if one is registered + if (auto * provider = effective_provider()) { + // Normalize FQNs before passing to plugin (strip leading '/') + std::vector normalized; + normalized.reserve(node_fqns.size()); + for (const auto & fqn : node_fqns) { + normalized.push_back(normalize_fqn(fqn)); + } + try { + auto entries = provider->get_logs(normalized, prefix_match, min_severity, context_filter, entity_id); + json items = json::array(); + for (const auto & e : entries) { + items.push_back(entry_to_json(e)); + } + return items; + } catch (const std::exception & e) { + RCLCPP_ERROR(node_->get_logger(), "LogProvider::get_logs threw: %s", e.what()); + return tl::make_unexpected(std::string("LogProvider plugin error: ") + e.what()); + } catch (...) { + RCLCPP_ERROR(node_->get_logger(), "LogProvider::get_logs threw unknown exception"); + return tl::make_unexpected(std::string("LogProvider plugin error: unknown exception")); + } + } + + // Default: query local ring buffer + // get_config() only fails on plugin errors; without a plugin (local path) it always succeeds. + auto cfg_result = get_config(entity_id); + if (!cfg_result) { + return tl::make_unexpected(cfg_result.error()); + } + LogConfig cfg = *cfg_result; + + // Effective minimum severity: stricter of entity config and query-param override + uint8_t min_level = severity_to_level(cfg.severity_filter); + if (!min_severity.empty() && is_valid_severity(min_severity)) { + uint8_t query_level = severity_to_level(min_severity); + if (query_level > min_level) { + min_level = query_level; + } + } + + std::vector collected; + + { + std::lock_guard lock(buffers_mutex_); + for (const auto & [buf_name, buf] : buffers_) { + bool matches = false; + for (const auto & fqn : node_fqns) { + const std::string norm = normalize_fqn(fqn); + // ROS 2 logger names use '.' as separator (e.g. "powertrain.engine.temp_sensor") + // while entity FQNs use '/' (e.g. "powertrain/engine/temp_sensor"). + // Try both slash-format and dot-format so the default ring buffer matches either. + std::string norm_dot = norm; + std::replace(norm_dot.begin(), norm_dot.end(), '/', '.'); + if (prefix_match) { + // Match exactly OR as a namespace prefix. + // Slash-format: prefix must be followed by '/' + // Dot-format: prefix must be followed by '.' + matches = (buf_name == norm) || (buf_name.rfind(norm + "/", 0) == 0) || (buf_name == norm_dot) || + (buf_name.rfind(norm_dot + ".", 0) == 0); + } else { + matches = (buf_name == norm) || (buf_name == norm_dot); + } + if (matches) { + break; + } + } + if (!matches) { + continue; + } + + for (const auto & entry : buf) { + if (entry.level < min_level) { + continue; + } + if (!context_filter.empty() && entry.name.find(context_filter) == std::string::npos) { + continue; + } + collected.push_back(entry); + } + } + } + + // Sort by id ascending + std::sort(collected.begin(), collected.end(), [](const LogEntry & a, const LogEntry & b) { + return a.id < b.id; + }); + + // Cap to max_entries (most recent N) + if (collected.size() > cfg.max_entries) { + collected.erase(collected.begin(), collected.begin() + static_cast(collected.size() - cfg.max_entries)); + } + + json items = json::array(); + for (const auto & e : collected) { + items.push_back(entry_to_json(e)); + } + return items; +} + +// --------------------------------------------------------------------------- +// Config management +// --------------------------------------------------------------------------- + +tl::expected LogManager::get_config(const std::string & entity_id) const { + if (auto * provider = effective_provider()) { + try { + return provider->get_config(entity_id); + } catch (const std::exception & e) { + RCLCPP_ERROR(node_->get_logger(), "LogProvider::get_config threw: %s", e.what()); + return tl::make_unexpected(std::string("LogProvider plugin error: ") + e.what()); + } catch (...) { + RCLCPP_ERROR(node_->get_logger(), "LogProvider::get_config threw unknown exception"); + return tl::make_unexpected(std::string("LogProvider plugin error: unknown exception")); + } + } + + std::lock_guard lock(configs_mutex_); + auto it = configs_.find(entity_id); + if (it != configs_.end()) { + return it->second; + } + return LogConfig{}; +} + +std::string LogManager::update_config(const std::string & entity_id, const std::optional & severity_filter, + const std::optional & max_entries) { + if (severity_filter.has_value() && !is_valid_severity(*severity_filter)) { + return "Invalid severity_filter '" + *severity_filter + "'. Must be one of: debug, info, warning, error, fatal"; + } + if (max_entries.has_value() && *max_entries == 0) { + return "max_entries must be greater than 0"; + } + + // If a plugin provider is registered, delegate config to it + if (auto * provider = effective_provider()) { + try { + return provider->update_config(entity_id, severity_filter, max_entries); + } catch (const std::exception & e) { + RCLCPP_ERROR(node_->get_logger(), "LogProvider::update_config threw: %s", e.what()); + return std::string("LogProvider plugin error: ") + e.what(); + } catch (...) { + RCLCPP_ERROR(node_->get_logger(), "LogProvider::update_config threw unknown exception"); + return "LogProvider plugin error: unknown exception"; + } + } + + std::lock_guard lock(configs_mutex_); + auto & cfg = configs_[entity_id]; + if (severity_filter.has_value()) { + cfg.severity_filter = *severity_filter; + } + if (max_entries.has_value()) { + cfg.max_entries = *max_entries; + } + return ""; +} + +} // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/src/plugins/plugin_loader.cpp b/src/ros2_medkit_gateway/src/plugins/plugin_loader.cpp index f4bb3f2a..774e706d 100644 --- a/src/ros2_medkit_gateway/src/plugins/plugin_loader.cpp +++ b/src/ros2_medkit_gateway/src/plugins/plugin_loader.cpp @@ -40,9 +40,11 @@ GatewayPluginLoadResult::GatewayPluginLoadResult(GatewayPluginLoadResult && othe : plugin(std::move(other.plugin)) , update_provider(other.update_provider) , introspection_provider(other.introspection_provider) + , log_provider(other.log_provider) , handle_(other.handle_) { other.update_provider = nullptr; other.introspection_provider = nullptr; + other.log_provider = nullptr; other.handle_ = nullptr; } @@ -51,6 +53,7 @@ GatewayPluginLoadResult & GatewayPluginLoadResult::operator=(GatewayPluginLoadRe // Destroy current state in correct order update_provider = nullptr; introspection_provider = nullptr; + log_provider = nullptr; plugin.reset(); if (handle_) { dlclose(handle_); @@ -60,10 +63,12 @@ GatewayPluginLoadResult & GatewayPluginLoadResult::operator=(GatewayPluginLoadRe plugin = std::move(other.plugin); update_provider = other.update_provider; introspection_provider = other.introspection_provider; + log_provider = other.log_provider; handle_ = other.handle_; other.update_provider = nullptr; other.introspection_provider = nullptr; + other.log_provider = nullptr; other.handle_ = nullptr; } return *this; @@ -186,6 +191,20 @@ tl::expected PluginLoader::load(const std: } } + using LogProviderFn = LogProvider * (*)(GatewayPlugin *); + auto log_fn = reinterpret_cast(dlsym(handle, "get_log_provider")); + if (log_fn) { + try { + result.log_provider = log_fn(raw_plugin); + } catch (const std::exception & e) { + RCLCPP_WARN(rclcpp::get_logger("plugin_loader"), "get_log_provider threw in %s: %s", plugin_path.c_str(), + e.what()); + } catch (...) { + RCLCPP_WARN(rclcpp::get_logger("plugin_loader"), "get_log_provider threw unknown exception in %s", + plugin_path.c_str()); + } + } + // Transfer handle ownership to result (disarm scope guard) result.handle_ = handle_guard.release(); return result; diff --git a/src/ros2_medkit_gateway/src/plugins/plugin_manager.cpp b/src/ros2_medkit_gateway/src/plugins/plugin_manager.cpp index afa19a80..3ef41c5d 100644 --- a/src/ros2_medkit_gateway/src/plugins/plugin_manager.cpp +++ b/src/ros2_medkit_gateway/src/plugins/plugin_manager.cpp @@ -55,6 +55,7 @@ void PluginManager::add_plugin(std::unique_ptr plugin) { // For in-process plugins, use dynamic_cast (safe within same binary) lp.update_provider = dynamic_cast(plugin.get()); lp.introspection_provider = dynamic_cast(plugin.get()); + lp.log_provider = dynamic_cast(plugin.get()); // Cache first UpdateProvider, warn on duplicates if (lp.update_provider) { @@ -65,6 +66,15 @@ void PluginManager::add_plugin(std::unique_ptr plugin) { } } + // Cache first LogProvider; additional LogProvider plugins are observers only + if (lp.log_provider) { + if (!first_log_provider_) { + first_log_provider_ = lp.log_provider; + } else { + RCLCPP_DEBUG(logger(), "LogProvider plugin '%s' registered as observer only", plugin->name().c_str()); + } + } + setup_plugin_logging(*plugin); lp.load_result.plugin = std::move(plugin); plugins_.push_back(std::move(lp)); @@ -83,6 +93,9 @@ size_t PluginManager::load_plugins(const std::vector & configs) { // Provider pointers from extern "C" query functions (safe across dlopen boundary) lp.update_provider = result->update_provider; lp.introspection_provider = result->introspection_provider; + // LogProvider: discovered via extern "C" query function (mirrors UpdateProvider / + // IntrospectionProvider mechanism โ€” safe across the dlopen boundary). + lp.log_provider = result->log_provider; // Cache first UpdateProvider, warn on duplicates if (lp.update_provider) { @@ -94,6 +107,15 @@ size_t PluginManager::load_plugins(const std::vector & configs) { } } + // Cache first LogProvider; additional LogProvider plugins are observers only + if (lp.log_provider) { + if (!first_log_provider_) { + first_log_provider_ = lp.log_provider; + } else { + RCLCPP_DEBUG(logger(), "LogProvider plugin '%s' registered as observer only", result->plugin->name().c_str()); + } + } + setup_plugin_logging(*result->plugin); lp.load_result = std::move(*result); plugins_.push_back(std::move(lp)); @@ -126,14 +148,26 @@ void PluginManager::disable_plugin(LoadedPlugin & lp) { } } } + if (first_log_provider_ && lp.log_provider == first_log_provider_) { + first_log_provider_ = nullptr; + for (const auto & other : plugins_) { + if (&other != &lp && other.load_result.plugin && other.log_provider) { + first_log_provider_ = other.log_provider; + break; + } + } + } lp.update_provider = nullptr; lp.introspection_provider = nullptr; + lp.log_provider = nullptr; lp.load_result.update_provider = nullptr; lp.load_result.introspection_provider = nullptr; + lp.load_result.log_provider = nullptr; lp.load_result.plugin.reset(); } void PluginManager::configure_plugins() { + std::unique_lock lock(plugins_mutex_); for (auto & lp : plugins_) { if (!lp.load_result.plugin) { continue; @@ -154,6 +188,7 @@ void PluginManager::configure_plugins() { void PluginManager::set_context(PluginContext & context) { context_ = &context; + std::unique_lock lock(plugins_mutex_); for (auto & lp : plugins_) { if (!lp.load_result.plugin) { continue; @@ -173,6 +208,7 @@ void PluginManager::set_context(PluginContext & context) { } void PluginManager::register_routes(httplib::Server & server, const std::string & api_prefix) { + std::unique_lock lock(plugins_mutex_); for (auto & lp : plugins_) { if (!lp.load_result.plugin) { continue; @@ -196,6 +232,7 @@ void PluginManager::shutdown_all() { return; } shutdown_called_ = true; + std::unique_lock lock(plugins_mutex_); for (auto & lp : plugins_) { if (!lp.load_result.plugin) { continue; @@ -212,10 +249,12 @@ void PluginManager::shutdown_all() { } UpdateProvider * PluginManager::get_update_provider() const { + std::shared_lock lock(plugins_mutex_); return first_update_provider_; } std::vector PluginManager::get_introspection_providers() const { + std::shared_lock lock(plugins_mutex_); std::vector result; for (const auto & lp : plugins_) { if (!lp.load_result.plugin) { @@ -228,7 +267,24 @@ std::vector PluginManager::get_introspection_providers( return result; } +LogProvider * PluginManager::get_log_provider() const { + std::shared_lock lock(plugins_mutex_); + return first_log_provider_; +} + +std::vector PluginManager::get_log_observers() const { + std::shared_lock lock(plugins_mutex_); + std::vector result; + for (const auto & lp : plugins_) { + if (lp.log_provider) { + result.push_back(lp.log_provider); + } + } + return result; +} + bool PluginManager::has_plugins() const { + std::shared_lock lock(plugins_mutex_); for (const auto & lp : plugins_) { if (lp.load_result.plugin) { return true; @@ -238,6 +294,7 @@ bool PluginManager::has_plugins() const { } std::vector PluginManager::plugin_names() const { + std::shared_lock lock(plugins_mutex_); std::vector names; for (const auto & lp : plugins_) { if (lp.load_result.plugin) { diff --git a/src/ros2_medkit_gateway/test/test_capability_builder.cpp b/src/ros2_medkit_gateway/test/test_capability_builder.cpp index 650ff1e7..def6a15d 100644 --- a/src/ros2_medkit_gateway/test/test_capability_builder.cpp +++ b/src/ros2_medkit_gateway/test/test_capability_builder.cpp @@ -63,6 +63,7 @@ TEST(CapabilityBuilderTest, CapabilityToNameReturnsCorrectStrings) { EXPECT_EQ(CapabilityBuilder::capability_to_name(Cap::RELATED_COMPONENTS), "related-components"); EXPECT_EQ(CapabilityBuilder::capability_to_name(Cap::RELATED_APPS), "related-apps"); EXPECT_EQ(CapabilityBuilder::capability_to_name(Cap::HOSTS), "hosts"); + EXPECT_EQ(CapabilityBuilder::capability_to_name(Cap::LOGS), "logs"); } TEST(CapabilityBuilderTest, CapabilityToPathMatchesName) { @@ -70,6 +71,7 @@ TEST(CapabilityBuilderTest, CapabilityToPathMatchesName) { EXPECT_EQ(CapabilityBuilder::capability_to_path(Cap::DATA), CapabilityBuilder::capability_to_name(Cap::DATA)); EXPECT_EQ(CapabilityBuilder::capability_to_path(Cap::RELATED_COMPONENTS), CapabilityBuilder::capability_to_name(Cap::RELATED_COMPONENTS)); + EXPECT_EQ(CapabilityBuilder::capability_to_path(Cap::LOGS), CapabilityBuilder::capability_to_name(Cap::LOGS)); } TEST(CapabilityBuilderTest, BuildsForDifferentEntityTypes) { diff --git a/src/ros2_medkit_gateway/test/test_log_handlers.cpp b/src/ros2_medkit_gateway/test/test_log_handlers.cpp new file mode 100644 index 00000000..e157633f --- /dev/null +++ b/src/ros2_medkit_gateway/test/test_log_handlers.cpp @@ -0,0 +1,131 @@ +// Copyright 2026 bburda +// +// 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 + +#include + +#include "ros2_medkit_gateway/http/error_codes.hpp" +#include "ros2_medkit_gateway/http/handlers/log_handlers.hpp" + +using json = nlohmann::json; +using ros2_medkit_gateway::AuthConfig; +using ros2_medkit_gateway::CorsConfig; +using ros2_medkit_gateway::TlsConfig; +using ros2_medkit_gateway::handlers::HandlerContext; +using ros2_medkit_gateway::handlers::LogHandlers; + +// LogHandlers uses a null GatewayNode and null AuthManager. +// This is safe because all three handler methods check req.matches.size() < 2 +// before accessing ctx_.node(), so default-constructed requests (size 0) return 400 first. + +class LogHandlersTest : public ::testing::Test { + protected: + CorsConfig cors_{}; + AuthConfig auth_{}; + TlsConfig tls_{}; + HandlerContext ctx_{nullptr, cors_, auth_, tls_, nullptr}; + LogHandlers handlers_{ctx_}; +}; + +// ============================================================================ +// handle_get_logs โ€” returns 400 when route matches are missing +// ============================================================================ + +// @verifies REQ_INTEROP_061 +TEST_F(LogHandlersTest, GetLogsReturnsBadRequestWhenMatchesMissing) { + // Default-constructed req has empty matches (size 0 < 2) + httplib::Request req; + httplib::Response res; + handlers_.handle_get_logs(req, res); + EXPECT_EQ(res.status, 400); +} + +// @verifies REQ_INTEROP_061 +TEST_F(LogHandlersTest, GetLogsBadRequestBodyIsValidJson) { + httplib::Request req; + httplib::Response res; + handlers_.handle_get_logs(req, res); + EXPECT_NO_THROW(json::parse(res.body)); +} + +// @verifies REQ_INTEROP_061 +TEST_F(LogHandlersTest, GetLogsBadRequestBodyContainsInvalidRequestErrorCode) { + httplib::Request req; + httplib::Response res; + handlers_.handle_get_logs(req, res); + auto body = json::parse(res.body); + ASSERT_TRUE(body.contains("error_code")); + EXPECT_EQ(body["error_code"], ros2_medkit_gateway::ERR_INVALID_REQUEST); +} + +// ============================================================================ +// handle_get_logs_configuration โ€” returns 400 when route matches are missing +// ============================================================================ + +// @verifies REQ_INTEROP_063 +TEST_F(LogHandlersTest, GetLogsConfigurationReturnsBadRequestWhenMatchesMissing) { + httplib::Request req; + httplib::Response res; + handlers_.handle_get_logs_configuration(req, res); + EXPECT_EQ(res.status, 400); +} + +// @verifies REQ_INTEROP_063 +TEST_F(LogHandlersTest, GetLogsConfigurationBadRequestBodyIsValidJson) { + httplib::Request req; + httplib::Response res; + handlers_.handle_get_logs_configuration(req, res); + EXPECT_NO_THROW(json::parse(res.body)); +} + +// @verifies REQ_INTEROP_063 +TEST_F(LogHandlersTest, GetLogsConfigurationBadRequestBodyContainsInvalidRequestErrorCode) { + httplib::Request req; + httplib::Response res; + handlers_.handle_get_logs_configuration(req, res); + auto body = json::parse(res.body); + ASSERT_TRUE(body.contains("error_code")); + EXPECT_EQ(body["error_code"], ros2_medkit_gateway::ERR_INVALID_REQUEST); +} + +// ============================================================================ +// handle_put_logs_configuration โ€” returns 400 when route matches are missing +// ============================================================================ + +// @verifies REQ_INTEROP_064 +TEST_F(LogHandlersTest, PutLogsConfigurationReturnsBadRequestWhenMatchesMissing) { + httplib::Request req; + httplib::Response res; + handlers_.handle_put_logs_configuration(req, res); + EXPECT_EQ(res.status, 400); +} + +// @verifies REQ_INTEROP_064 +TEST_F(LogHandlersTest, PutLogsConfigurationBadRequestBodyIsValidJson) { + httplib::Request req; + httplib::Response res; + handlers_.handle_put_logs_configuration(req, res); + EXPECT_NO_THROW(json::parse(res.body)); +} + +// @verifies REQ_INTEROP_064 +TEST_F(LogHandlersTest, PutLogsConfigurationBadRequestBodyContainsInvalidRequestErrorCode) { + httplib::Request req; + httplib::Response res; + handlers_.handle_put_logs_configuration(req, res); + auto body = json::parse(res.body); + ASSERT_TRUE(body.contains("error_code")); + EXPECT_EQ(body["error_code"], ros2_medkit_gateway::ERR_INVALID_REQUEST); +} diff --git a/src/ros2_medkit_gateway/test/test_log_manager.cpp b/src/ros2_medkit_gateway/test/test_log_manager.cpp new file mode 100644 index 00000000..0119e903 --- /dev/null +++ b/src/ros2_medkit_gateway/test/test_log_manager.cpp @@ -0,0 +1,674 @@ +// Copyright 2026 bburda +// +// 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 +#include +#include + +#include "ros2_medkit_gateway/log_manager.hpp" +#include "ros2_medkit_gateway/plugins/gateway_plugin.hpp" +#include "ros2_medkit_gateway/plugins/plugin_manager.hpp" +#include "ros2_medkit_gateway/providers/log_provider.hpp" + +using json = nlohmann::json; +using ros2_medkit_gateway::LogConfig; +using ros2_medkit_gateway::LogEntry; +using ros2_medkit_gateway::LogManager; + +// ============================================================ +// Static utility tests โ€” no ROS 2 node required +// ============================================================ + +// @verifies REQ_INTEROP_061 +TEST(LogManagerSeverityTest, LevelToSeverityMapping) { + EXPECT_EQ(LogManager::level_to_severity(10), "debug"); + EXPECT_EQ(LogManager::level_to_severity(20), "info"); + EXPECT_EQ(LogManager::level_to_severity(30), "warning"); + EXPECT_EQ(LogManager::level_to_severity(40), "error"); + EXPECT_EQ(LogManager::level_to_severity(50), "fatal"); + // Unknown level defaults to debug + EXPECT_EQ(LogManager::level_to_severity(0), "debug"); + EXPECT_EQ(LogManager::level_to_severity(99), "debug"); +} + +// @verifies REQ_INTEROP_061 +TEST(LogManagerSeverityTest, SeverityToLevelMapping) { + EXPECT_EQ(LogManager::severity_to_level("debug"), 10); + EXPECT_EQ(LogManager::severity_to_level("info"), 20); + EXPECT_EQ(LogManager::severity_to_level("warning"), 30); + EXPECT_EQ(LogManager::severity_to_level("error"), 40); + EXPECT_EQ(LogManager::severity_to_level("fatal"), 50); + // Invalid -> 0 + EXPECT_EQ(LogManager::severity_to_level(""), 0); + EXPECT_EQ(LogManager::severity_to_level("unknown"), 0); + EXPECT_EQ(LogManager::severity_to_level("WARN"), 0); // case-sensitive + EXPECT_EQ(LogManager::severity_to_level("warn"), 0); // ROS 2 name, not SOVD name +} + +// @verifies REQ_INTEROP_061 +TEST(LogManagerSeverityTest, IsValidSeverity) { + EXPECT_TRUE(LogManager::is_valid_severity("debug")); + EXPECT_TRUE(LogManager::is_valid_severity("info")); + EXPECT_TRUE(LogManager::is_valid_severity("warning")); + EXPECT_TRUE(LogManager::is_valid_severity("error")); + EXPECT_TRUE(LogManager::is_valid_severity("fatal")); + EXPECT_FALSE(LogManager::is_valid_severity("warn")); // ROS 2 name + EXPECT_FALSE(LogManager::is_valid_severity("")); + EXPECT_FALSE(LogManager::is_valid_severity("WARN")); + EXPECT_FALSE(LogManager::is_valid_severity("INFORMATION")); + EXPECT_FALSE(LogManager::is_valid_severity("verbose")); +} + +// @verifies REQ_INTEROP_061 +TEST(LogManagerFqnTest, NormalizeStripsLeadingSlash) { + EXPECT_EQ(LogManager::normalize_fqn("/powertrain/engine/temp_sensor"), "powertrain/engine/temp_sensor"); + EXPECT_EQ(LogManager::normalize_fqn("/perception/lidar/lidar_sensor"), "perception/lidar/lidar_sensor"); +} + +// @verifies REQ_INTEROP_061 +TEST(LogManagerFqnTest, NormalizeNoLeadingSlashUnchanged) { + EXPECT_EQ(LogManager::normalize_fqn("powertrain/engine/temp_sensor"), "powertrain/engine/temp_sensor"); + EXPECT_EQ(LogManager::normalize_fqn("temp_sensor"), "temp_sensor"); +} + +// @verifies REQ_INTEROP_061 +TEST(LogManagerFqnTest, NormalizeEmptyStringUnchanged) { + EXPECT_EQ(LogManager::normalize_fqn(""), ""); +} + +// @verifies REQ_INTEROP_061 +TEST(LogManagerEntryToJsonTest, BasicFields) { + LogEntry entry; + entry.id = 42; + entry.stamp_sec = 1707044400; + entry.stamp_nanosec = 123456789; + entry.level = 30; // warning + entry.name = "powertrain/engine/temp_sensor"; // no leading slash + entry.msg = "Calibration drift detected"; + entry.function = "read_sensor"; + entry.file = "temp_sensor.cpp"; + entry.line = 99; + + auto j = LogManager::entry_to_json(entry); + + EXPECT_EQ(j["id"], "log_42"); + EXPECT_EQ(j["severity"], "warning"); + EXPECT_EQ(j["message"], "Calibration drift detected"); + + // Timestamp must be ISO 8601 with Z suffix + const auto & ts = j["timestamp"].get(); + EXPECT_EQ(ts.back(), 'Z'); + EXPECT_NE(ts.find('T'), std::string::npos); + // Context + EXPECT_EQ(j["context"]["node"], "powertrain/engine/temp_sensor"); + EXPECT_EQ(j["context"]["function"], "read_sensor"); + EXPECT_EQ(j["context"]["file"], "temp_sensor.cpp"); + EXPECT_EQ(j["context"]["line"], 99); +} + +// @verifies REQ_INTEROP_061 +TEST(LogManagerEntryToJsonTest, EmptyOptionalFieldsOmitted) { + LogEntry entry; + entry.id = 1; + entry.stamp_sec = 0; + entry.stamp_nanosec = 0; + entry.level = 20; + entry.name = "my_node"; + entry.msg = "hello"; + entry.function = ""; // empty -> omitted + entry.file = ""; // empty -> omitted + entry.line = 0; // zero -> omitted + + auto j = LogManager::entry_to_json(entry); + + EXPECT_TRUE(j["context"].contains("node")); + EXPECT_FALSE(j["context"].contains("function")); + EXPECT_FALSE(j["context"].contains("file")); + EXPECT_FALSE(j["context"].contains("line")); +} + +// @verifies REQ_INTEROP_061 +TEST(LogManagerEntryToJsonTest, AllSeverityLevels) { + for (const auto & [level, expected] : std::vector>{ + {10, "debug"}, {20, "info"}, {30, "warning"}, {40, "error"}, {50, "fatal"}}) { + LogEntry e{}; + e.id = 1; + e.level = level; + e.name = "n"; + e.msg = "m"; + EXPECT_EQ(LogManager::entry_to_json(e)["severity"], expected) << "level=" << int(level); + } +} + +// ============================================================ +// Ring buffer tests โ€” require a ROS 2 node for LogManager construction +// but use inject_entry_for_testing() to bypass /rosout +// ============================================================ + +class LogManagerBufferTest : public ::testing::Test { + protected: + void SetUp() override { + rclcpp::init(0, nullptr); + node_ = std::make_shared("test_log_manager"); + // Small buffer size of 3 for easy eviction testing + mgr_ = std::make_unique(node_.get(), nullptr, /*max_buffer_size=*/3); + } + + void TearDown() override { + mgr_.reset(); + node_.reset(); + rclcpp::shutdown(); + } + + LogEntry make_entry(int64_t id, const std::string & name, uint8_t level = 20) { + LogEntry e{}; + e.id = id; + e.stamp_sec = id; + e.stamp_nanosec = 0; + e.level = level; + e.name = name; + e.msg = "msg " + std::to_string(id); + return e; + } + + std::shared_ptr node_; + std::unique_ptr mgr_; +}; + +// @verifies REQ_INTEROP_061 +TEST_F(LogManagerBufferTest, RingBufferEvictsOldestEntryWhenFull) { + // Buffer size is 3; inject 4 entries for the same node + mgr_->inject_entry_for_testing(make_entry(1, "my_node")); + mgr_->inject_entry_for_testing(make_entry(2, "my_node")); + mgr_->inject_entry_for_testing(make_entry(3, "my_node")); + mgr_->inject_entry_for_testing(make_entry(4, "my_node")); // evicts id=1 + + auto result = mgr_->get_logs({"/my_node"}, false, "", "", ""); + ASSERT_TRUE(result.has_value()); + ASSERT_EQ(result->size(), 3u); + // Oldest (id=1) must be gone; newest 3 remain + EXPECT_EQ((*result)[0]["id"], "log_2"); + EXPECT_EQ((*result)[1]["id"], "log_3"); + EXPECT_EQ((*result)[2]["id"], "log_4"); +} + +// @verifies REQ_INTEROP_061 +TEST_F(LogManagerBufferTest, FqnWithLeadingSlashMatchesBuffer) { + // Buffer stores entries under "my_ns/my_node" (no leading slash) + // Entity FQN from entity cache is "/my_ns/my_node" (with leading slash) + // get_logs() must normalize and still find the entries + mgr_->inject_entry_for_testing(make_entry(10, "my_ns/my_node")); + + auto result = mgr_->get_logs({"/my_ns/my_node"}, false, "", "", ""); + ASSERT_TRUE(result.has_value()); + ASSERT_EQ(result->size(), 1u); + EXPECT_EQ((*result)[0]["id"], "log_10"); +} + +// @verifies REQ_INTEROP_061 +TEST_F(LogManagerBufferTest, SeverityFilterExcludesLowerLevels) { + // inject debug(10), info(20), warning(30) + mgr_->inject_entry_for_testing(make_entry(1, "n", 10)); + mgr_->inject_entry_for_testing(make_entry(2, "n", 20)); + mgr_->inject_entry_for_testing(make_entry(3, "n", 30)); + + // min_severity=warning -> only warning (30) should appear + auto result = mgr_->get_logs({"/n"}, false, "warning", "", ""); + ASSERT_TRUE(result.has_value()); + ASSERT_EQ(result->size(), 1u); + EXPECT_EQ((*result)[0]["severity"], "warning"); +} + +// @verifies REQ_INTEROP_061 +TEST_F(LogManagerBufferTest, PrefixMatchIncludesChildNamespaces) { + // Component "engine" prefix-matches "engine/temp_sensor" and "engine/pressure" + // but NOT "engine_control/sensor" (different namespace) + mgr_->inject_entry_for_testing(make_entry(1, "engine/temp_sensor")); + mgr_->inject_entry_for_testing(make_entry(2, "engine/pressure")); + mgr_->inject_entry_for_testing(make_entry(3, "engine_control/sensor")); + + auto result = mgr_->get_logs({"/engine"}, true, "", "", ""); + ASSERT_TRUE(result.has_value()); + ASSERT_EQ(result->size(), 2u); + EXPECT_EQ((*result)[0]["id"], "log_1"); + EXPECT_EQ((*result)[1]["id"], "log_2"); +} + +// @verifies REQ_INTEROP_061 +TEST_F(LogManagerBufferTest, PrefixMatchDoesNotFalsePositiveOnSubstring) { + // "engine" must NOT match "engine_control" (only full namespace segments) + mgr_->inject_entry_for_testing(make_entry(1, "engine_control/sensor")); + + auto result = mgr_->get_logs({"/engine"}, true, "", "", ""); + ASSERT_TRUE(result.has_value()); + EXPECT_EQ(result->size(), 0u); +} + +// @verifies REQ_INTEROP_061 +TEST_F(LogManagerBufferTest, MaxEntriesCapsMostRecentEntries) { + // Inject 5 entries, set max_entries=2 via config + for (int i = 1; i <= 5; ++i) { + mgr_->inject_entry_for_testing(make_entry(i, "n")); + } + mgr_->update_config("my_entity", std::nullopt, 2u); + + auto result = mgr_->get_logs({"/n"}, false, "", "", "my_entity"); + ASSERT_TRUE(result.has_value()); + ASSERT_EQ(result->size(), 2u); + // Most recent 2: ids 4 and 5 + EXPECT_EQ((*result)[0]["id"], "log_4"); + EXPECT_EQ((*result)[1]["id"], "log_5"); +} + +// @verifies REQ_INTEROP_061 +TEST_F(LogManagerBufferTest, ContextFilterMatchesSubstring) { + mgr_->inject_entry_for_testing(make_entry(1, "powertrain/engine/temp_sensor")); + mgr_->inject_entry_for_testing(make_entry(2, "powertrain/engine/pressure")); + mgr_->inject_entry_for_testing(make_entry(3, "powertrain/gearbox/speed")); + + // context_filter="temp" -> only temp_sensor + auto result = mgr_->get_logs({"/powertrain"}, true, "", "temp", ""); + ASSERT_TRUE(result.has_value()); + ASSERT_EQ(result->size(), 1u); + EXPECT_EQ((*result)[0]["context"]["node"], "powertrain/engine/temp_sensor"); +} + +// @verifies REQ_INTEROP_061 +TEST_F(LogManagerBufferTest, GetLogsMatchesDotNotationLoggerNames) { + // ROS 2 rosout messages carry logger names using '.' as separator + // (e.g. "powertrain.engine.temp_sensor") while entity FQNs use '/'. + // get_logs() must match entries stored under dot-format keys. + mgr_->inject_entry_for_testing(make_entry(1, "powertrain.engine.temp_sensor")); + mgr_->inject_entry_for_testing(make_entry(2, "powertrain.gearbox.speed_sensor")); + + // Exact match: app FQN "/powertrain/engine/temp_sensor" must resolve dot-format entry + auto result = mgr_->get_logs({"/powertrain/engine/temp_sensor"}, false, "", "", "temp_sensor"); + ASSERT_TRUE(result.has_value()); + ASSERT_EQ(result->size(), 1u); + EXPECT_EQ((*result)[0]["context"]["node"], "powertrain.engine.temp_sensor"); +} + +// @verifies REQ_INTEROP_061 +TEST_F(LogManagerBufferTest, GetLogsPrefixMatchesDotNotationLoggerNames) { + // Component namespace prefix matching must also work against dot-format logger names. + mgr_->inject_entry_for_testing(make_entry(1, "powertrain.engine.temp_sensor")); + mgr_->inject_entry_for_testing(make_entry(2, "powertrain.engine.rpm_sensor")); + mgr_->inject_entry_for_testing(make_entry(3, "chassis.brakes.pressure_sensor")); + + // Prefix match: component FQN "/powertrain/engine" should cover both powertrain nodes + auto result = mgr_->get_logs({"/powertrain/engine"}, true, "", "", "comp"); + ASSERT_TRUE(result.has_value()); + ASSERT_EQ(result->size(), 2u); +} + +// @verifies REQ_INTEROP_064 +TEST_F(LogManagerBufferTest, UpdateConfigRejectsInvalidSeverity) { + auto err = mgr_->update_config("e", std::string("verbose"), std::nullopt); + EXPECT_FALSE(err.empty()); +} + +// @verifies REQ_INTEROP_064 +TEST_F(LogManagerBufferTest, UpdateConfigRejectsZeroMaxEntries) { + auto err = mgr_->update_config("e", std::nullopt, size_t{0}); + EXPECT_FALSE(err.empty()); +} + +// @verifies REQ_INTEROP_063 +TEST_F(LogManagerBufferTest, GetConfigReturnsDefaultsForUnknownEntity) { + auto cfg = mgr_->get_config("unknown_entity"); + ASSERT_TRUE(cfg.has_value()); + EXPECT_EQ(cfg->severity_filter, "debug"); + EXPECT_EQ(cfg->max_entries, 100u); +} + +// @verifies REQ_INTEROP_064 +TEST_F(LogManagerBufferTest, PartialConfigUpdatePreservesOtherField) { + mgr_->update_config("e", std::string("warning"), std::nullopt); + mgr_->update_config("e", std::nullopt, size_t{500}); + auto cfg = mgr_->get_config("e"); + ASSERT_TRUE(cfg.has_value()); + EXPECT_EQ(cfg->severity_filter, "warning"); + EXPECT_EQ(cfg->max_entries, 500u); +} + +// ============================================================ +// Mock LogProvider plugins for manages_ingestion() tests +// ============================================================ + +namespace { + +using ros2_medkit_gateway::GatewayPlugin; +using ros2_medkit_gateway::LogProvider; +using ros2_medkit_gateway::PluginManager; + +/// LogProvider that manages its own ingestion (manages_ingestion() == true). +/// Tracks calls and returns canned responses. +class MockIngestionPlugin : public GatewayPlugin, public LogProvider { + public: + std::string name() const override { + return "mock_ingestion"; + } + void configure(const json & /*config*/) override { + } + + bool manages_ingestion() const override { + return true; + } + + std::vector get_logs(const std::vector & /*node_fqns*/, bool /*prefix_match*/, + const std::string & /*min_severity*/, const std::string & /*context_filter*/, + const std::string & /*entity_id*/) override { + get_logs_called = true; + return canned_entries; + } + + LogConfig get_config(const std::string & entity_id) const override { + get_config_called = true; + auto it = configs.find(entity_id); + if (it != configs.end()) { + return it->second; + } + return LogConfig{}; + } + + std::string update_config(const std::string & entity_id, const std::optional & severity_filter, + const std::optional & max_entries) override { + update_config_called = true; + auto & cfg = configs[entity_id]; + if (severity_filter.has_value()) { + cfg.severity_filter = *severity_filter; + } + if (max_entries.has_value()) { + cfg.max_entries = *max_entries; + } + return ""; + } + + std::vector canned_entries = [] { + LogEntry e{}; + e.id = 1; + e.stamp_sec = 1000; + e.stamp_nanosec = 0; + e.level = 20; + e.name = "plugin_node"; + e.msg = "from plugin"; + return std::vector{e}; + }(); + + mutable bool get_logs_called = false; + mutable bool get_config_called = false; + mutable bool update_config_called = false; + std::unordered_map configs; +}; + +/// LogProvider with default manages_ingestion() == false (observer/passive mode). +class MockPassivePlugin : public GatewayPlugin, public LogProvider { + public: + std::string name() const override { + return "mock_passive"; + } + void configure(const json & /*config*/) override { + } + + std::vector get_logs(const std::vector & /*node_fqns*/, bool /*prefix_match*/, + const std::string & /*min_severity*/, const std::string & /*context_filter*/, + const std::string & /*entity_id*/) override { + get_logs_called = true; + return canned_entries; + } + + LogConfig get_config(const std::string & entity_id) const override { + get_config_called = true; + auto it = configs.find(entity_id); + if (it != configs.end()) { + return it->second; + } + return LogConfig{}; + } + + std::string update_config(const std::string & entity_id, const std::optional & severity_filter, + const std::optional & max_entries) override { + update_config_called = true; + auto & cfg = configs[entity_id]; + if (severity_filter.has_value()) { + cfg.severity_filter = *severity_filter; + } + if (max_entries.has_value()) { + cfg.max_entries = *max_entries; + } + return ""; + } + + std::vector canned_entries = [] { + LogEntry e{}; + e.id = 1; + e.stamp_sec = 1000; + e.stamp_nanosec = 0; + e.level = 30; + e.name = "passive_node"; + e.msg = "from passive"; + return std::vector{e}; + }(); + + mutable bool get_logs_called = false; + mutable bool get_config_called = false; + mutable bool update_config_called = false; + std::unordered_map configs; +}; + +/// Plugin that throws on get_logs() and get_config() +class MockThrowingLogPlugin : public GatewayPlugin, public LogProvider { + public: + std::string name() const override { + return "mock_throwing_log"; + } + void configure(const json & /*config*/) override { + } + + std::vector get_logs(const std::vector & /*node_fqns*/, bool /*prefix_match*/, + const std::string & /*min_severity*/, const std::string & /*context_filter*/, + const std::string & /*entity_id*/) override { + throw std::runtime_error("plugin get_logs failed"); + } + + LogConfig get_config(const std::string & /*entity_id*/) const override { + throw std::runtime_error("plugin get_config failed"); + } + + std::string update_config(const std::string & /*entity_id*/, const std::optional & /*severity_filter*/, + const std::optional & /*max_entries*/) override { + return ""; + } +}; + +} // namespace + +// ============================================================ +// LogManagerIngestionTest fixture +// ============================================================ + +class LogManagerIngestionTest : public ::testing::Test { + protected: + void SetUp() override { + rclcpp::init(0, nullptr); + node_ = std::make_shared("test_log_ingestion"); + } + + void TearDown() override { + mgr_.reset(); + plugin_mgr_.reset(); + node_.reset(); + rclcpp::shutdown(); + } + + LogEntry make_entry(int64_t id, const std::string & name, uint8_t level = 20) { + LogEntry e{}; + e.id = id; + e.stamp_sec = id; + e.stamp_nanosec = 0; + e.level = level; + e.name = name; + e.msg = "msg " + std::to_string(id); + return e; + } + + std::shared_ptr node_; + std::unique_ptr plugin_mgr_; + std::unique_ptr mgr_; +}; + +// @verifies REQ_INTEROP_061 +TEST_F(LogManagerIngestionTest, ManagesIngestionDelegatesToPlugin) { + plugin_mgr_ = std::make_unique(); + auto plugin = std::make_unique(); + auto * raw = plugin.get(); + plugin_mgr_->add_plugin(std::move(plugin)); + + mgr_ = std::make_unique(node_.get(), plugin_mgr_.get(), 10); + + auto result = mgr_->get_logs({"/my_node"}, false, "", "", "entity1"); + EXPECT_TRUE(raw->get_logs_called); + ASSERT_TRUE(result.has_value()); + ASSERT_EQ(result->size(), 1u); + EXPECT_EQ((*result)[0]["id"], "log_1"); + EXPECT_EQ((*result)[0]["message"], "from plugin"); +} + +// @verifies REQ_INTEROP_064 +TEST_F(LogManagerIngestionTest, ManagesIngestionUpdateConfigDelegatesToPlugin) { + plugin_mgr_ = std::make_unique(); + auto plugin = std::make_unique(); + auto * raw = plugin.get(); + plugin_mgr_->add_plugin(std::move(plugin)); + + mgr_ = std::make_unique(node_.get(), plugin_mgr_.get(), 10); + + auto err = mgr_->update_config("entity1", std::string("error"), std::nullopt); + EXPECT_TRUE(err.empty()); + EXPECT_TRUE(raw->update_config_called); + EXPECT_EQ(raw->configs["entity1"].severity_filter, "error"); +} + +// @verifies REQ_INTEROP_063 +TEST_F(LogManagerIngestionTest, ManagesIngestionGetConfigDelegatesToPlugin) { + plugin_mgr_ = std::make_unique(); + auto plugin = std::make_unique(); + auto * raw = plugin.get(); + // Pre-populate plugin config + raw->configs["entity1"] = LogConfig{"warning", 50}; + plugin_mgr_->add_plugin(std::move(plugin)); + + mgr_ = std::make_unique(node_.get(), plugin_mgr_.get(), 10); + + auto cfg = mgr_->get_config("entity1"); + EXPECT_TRUE(raw->get_config_called); + ASSERT_TRUE(cfg.has_value()); + EXPECT_EQ(cfg->severity_filter, "warning"); + EXPECT_EQ(cfg->max_entries, 50u); +} + +// @verifies REQ_INTEROP_061 +TEST_F(LogManagerIngestionTest, ManagesIngestionLocalBufferBypassed) { + plugin_mgr_ = std::make_unique(); + auto plugin = std::make_unique(); + // Plugin returns empty vector for get_logs + plugin->canned_entries.clear(); + plugin_mgr_->add_plugin(std::move(plugin)); + + mgr_ = std::make_unique(node_.get(), plugin_mgr_.get(), 10); + + // Inject entries into local buffer - these should be invisible because plugin owns queries + mgr_->inject_entry_for_testing(make_entry(1, "my_node")); + mgr_->inject_entry_for_testing(make_entry(2, "my_node")); + + auto result = mgr_->get_logs({"/my_node"}, false, "", "", ""); + ASSERT_TRUE(result.has_value()); + // Plugin returns empty - local buffer entries are not visible + EXPECT_EQ(result->size(), 0u); +} + +// @verifies REQ_INTEROP_061 +TEST_F(LogManagerIngestionTest, DefaultManagesIngestionPreservesCurrentBehavior) { + plugin_mgr_ = std::make_unique(); + auto plugin = std::make_unique(); + auto * raw = plugin.get(); + plugin_mgr_->add_plugin(std::move(plugin)); + + mgr_ = std::make_unique(node_.get(), plugin_mgr_.get(), 10); + + auto result = mgr_->get_logs({"/node1"}, false, "", "", ""); + // Passive plugin still receives get_logs() delegation + EXPECT_TRUE(raw->get_logs_called); + ASSERT_TRUE(result.has_value()); + ASSERT_EQ(result->size(), 1u); + EXPECT_EQ((*result)[0]["id"], "log_1"); + EXPECT_EQ((*result)[0]["message"], "from passive"); +} + +// @verifies REQ_INTEROP_061 +TEST_F(LogManagerIngestionTest, NoPluginPreservesDefaultBehavior) { + // No plugin manager at all - ring buffer works as before + mgr_ = std::make_unique(node_.get(), nullptr, 10); + + mgr_->inject_entry_for_testing(make_entry(1, "my_node")); + mgr_->inject_entry_for_testing(make_entry(2, "my_node")); + + auto result = mgr_->get_logs({"/my_node"}, false, "", "", ""); + ASSERT_TRUE(result.has_value()); + ASSERT_EQ(result->size(), 2u); + EXPECT_EQ((*result)[0]["id"], "log_1"); + EXPECT_EQ((*result)[1]["id"], "log_2"); +} + +// @verifies REQ_INTEROP_064 +TEST_F(LogManagerIngestionTest, ManagesIngestionStillValidatesBeforeDelegation) { + plugin_mgr_ = std::make_unique(); + auto plugin = std::make_unique(); + auto * raw = plugin.get(); + plugin_mgr_->add_plugin(std::move(plugin)); + + mgr_ = std::make_unique(node_.get(), plugin_mgr_.get(), 10); + + // LogManager validates severity before delegating - "verbose" is invalid + auto err = mgr_->update_config("e", std::string("verbose"), std::nullopt); + EXPECT_FALSE(err.empty()); + EXPECT_FALSE(raw->update_config_called); + + // Also validate max_entries=0 + auto err2 = mgr_->update_config("e", std::nullopt, size_t{0}); + EXPECT_FALSE(err2.empty()); + EXPECT_FALSE(raw->update_config_called); +} + +// @verifies REQ_INTEROP_061 +TEST_F(LogManagerIngestionTest, PluginGetLogsThrowReturnsError) { + plugin_mgr_ = std::make_unique(); + plugin_mgr_->add_plugin(std::make_unique()); + mgr_ = std::make_unique(node_.get(), plugin_mgr_.get(), 10); + + auto result = mgr_->get_logs({"/node"}, false, "", "", ""); + ASSERT_FALSE(result.has_value()); + EXPECT_NE(result.error().find("plugin get_logs failed"), std::string::npos); +} + +// @verifies REQ_INTEROP_063 +TEST_F(LogManagerIngestionTest, PluginGetConfigThrowReturnsError) { + plugin_mgr_ = std::make_unique(); + plugin_mgr_->add_plugin(std::make_unique()); + mgr_ = std::make_unique(node_.get(), plugin_mgr_.get(), 10); + + auto result = mgr_->get_config("entity1"); + ASSERT_FALSE(result.has_value()); + EXPECT_NE(result.error().find("plugin get_config failed"), std::string::npos); +} diff --git a/src/ros2_medkit_gateway/test/test_plugin_manager.cpp b/src/ros2_medkit_gateway/test/test_plugin_manager.cpp index 06c452c8..4cf41167 100644 --- a/src/ros2_medkit_gateway/test/test_plugin_manager.cpp +++ b/src/ros2_medkit_gateway/test/test_plugin_manager.cpp @@ -15,6 +15,10 @@ #include #include +#include +#include +#include + #include "ros2_medkit_gateway/plugins/plugin_context.hpp" #include "ros2_medkit_gateway/plugins/plugin_manager.hpp" #include "ros2_medkit_gateway/providers/introspection_provider.hpp" @@ -349,3 +353,122 @@ TEST(PluginManagerTest, ShutdownSwallowsExceptions) { EXPECT_NO_THROW(mgr.shutdown_all()); EXPECT_TRUE(good_raw->shutdown_called_); } + +using namespace std::chrono_literals; + +// Test 1: Concurrent readers don't block each other +TEST(PluginManagerConcurrencyTest, ConcurrentReadsDoNotBlock) { + PluginManager mgr; + mgr.add_plugin(std::make_unique()); + mgr.add_plugin(std::make_unique()); + + std::atomic completed{0}; + std::vector readers; + + for (int i = 0; i < 8; ++i) { + readers.emplace_back([&mgr, &completed] { + for (int j = 0; j < 200; ++j) { + auto up = mgr.get_update_provider(); + auto ips = mgr.get_introspection_providers(); + auto lp = mgr.get_log_provider(); + auto obs = mgr.get_log_observers(); + auto has = mgr.has_plugins(); + auto names = mgr.plugin_names(); + (void)up; + (void)ips; + (void)lp; + (void)obs; + (void)has; + (void)names; + } + completed++; + }); + } + + auto start = std::chrono::high_resolution_clock::now(); + for (auto & t : readers) { + t.join(); + } + auto duration = std::chrono::high_resolution_clock::now() - start; + + EXPECT_EQ(completed.load(), 8); + EXPECT_LT(duration, 2s) << "Concurrent reads took too long - possible blocking"; +} + +// Test 2: Concurrent reads and writes (lifecycle/disable) don't deadlock +TEST(PluginManagerConcurrencyTest, ConcurrentReadsAndLifecycleDoNotDeadlock) { + PluginManager mgr; + mgr.add_plugin(std::make_unique()); + mgr.add_plugin(std::make_unique()); + + std::atomic keep_running{true}; + std::atomic read_count{0}; + std::atomic write_count{0}; + + // Multiple reader threads (simulating ROS 2 executor calling get_log_observers) + std::vector readers; + for (int i = 0; i < 4; ++i) { + readers.emplace_back([&mgr, &keep_running, &read_count] { + while (keep_running) { + auto obs = mgr.get_log_observers(); + auto ips = mgr.get_introspection_providers(); + auto up = mgr.get_update_provider(); + (void)obs; + (void)ips; + (void)up; + read_count++; + } + }); + } + + // Writer thread (simulating lifecycle operations that take unique_lock) + std::thread writer([&mgr, &keep_running, &write_count] { + while (keep_running) { + mgr.configure_plugins(); + write_count++; + } + }); + + std::this_thread::sleep_for(50ms); + keep_running = false; + + for (auto & t : readers) { + t.join(); + } + writer.join(); + + EXPECT_GT(read_count.load(), 0) << "Readers made no progress - possible deadlock"; + EXPECT_GT(write_count.load(), 0) << "Writer made no progress - possible deadlock"; +} + +// Test 3: Shutdown while readers are active doesn't deadlock +TEST(PluginManagerConcurrencyTest, ShutdownWhileReadersActiveDoesNotDeadlock) { + auto mgr = std::make_unique(); + mgr->add_plugin(std::make_unique()); + + std::atomic keep_running{true}; + std::atomic read_count{0}; + + std::vector readers; + for (int i = 0; i < 4; ++i) { + readers.emplace_back([&mgr, &keep_running, &read_count] { + while (keep_running) { + if (mgr) { + auto obs = mgr->get_log_observers(); + (void)obs; + } + read_count++; + } + }); + } + + std::this_thread::sleep_for(10ms); + mgr->shutdown_all(); + + keep_running = false; + for (auto & t : readers) { + t.join(); + } + + EXPECT_GT(read_count.load(), 0) << "Readers made no progress before shutdown"; +} diff --git a/src/ros2_medkit_integration_tests/ros2_medkit_test_utils/gateway_test_case.py b/src/ros2_medkit_integration_tests/ros2_medkit_test_utils/gateway_test_case.py index 7ad6eb1c..27370bce 100644 --- a/src/ros2_medkit_integration_tests/ros2_medkit_test_utils/gateway_test_case.py +++ b/src/ros2_medkit_integration_tests/ros2_medkit_test_utils/gateway_test_case.py @@ -378,6 +378,41 @@ def get_raw(self, endpoint, *, timeout=10, expected_status=200, **kwargs): ) return response + def put_raw(self, endpoint, data, *, timeout=10, expected_status=200, **kwargs): + """Send PUT with JSON body and return the raw ``Response`` (no JSON parsing). + + Useful when the caller needs to inspect headers or the response body + without asserting it is valid JSON (e.g. testing error responses). + + Parameters + ---------- + endpoint : str + Path relative to ``BASE_URL``. + data : dict + JSON-serializable request body. + timeout : int + Request timeout in seconds. + expected_status : int + Expected HTTP status code. + **kwargs + Extra keyword arguments forwarded to ``requests.put()``. + + Returns + ------- + requests.Response + The raw response object. + + """ + response = requests.put( + f'{self.BASE_URL}{endpoint}', json=data, timeout=timeout, **kwargs + ) + self.assertEqual( + response.status_code, + expected_status, + f'PUT {endpoint} returned {response.status_code}: {response.text}', + ) + return response + # ------------------------------------------------------------------ # Waiters # ------------------------------------------------------------------ diff --git a/src/ros2_medkit_integration_tests/test/features/test_logging_api.test.py b/src/ros2_medkit_integration_tests/test/features/test_logging_api.test.py new file mode 100644 index 00000000..23f8b15d --- /dev/null +++ b/src/ros2_medkit_integration_tests/test/features/test_logging_api.test.py @@ -0,0 +1,372 @@ +#!/usr/bin/env python3 +# Copyright 2026 bburda +# +# 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. + +"""Feature tests for communication log REST API endpoints. + +Validates GET /logs, GET /logs/configuration, and PUT /logs/configuration +for both App and Component entities. + +- App log queries use exact FQN matching. +- Component log queries use namespace prefix matching (all nodes under + the component namespace are included). + +""" + +import unittest + +import launch_testing +import launch_testing.actions + +from ros2_medkit_test_utils.constants import ALLOWED_EXIT_CODES +from ros2_medkit_test_utils.gateway_test_case import GatewayTestCase +from ros2_medkit_test_utils.launch_helpers import create_test_launch + + +def generate_test_description(): + return create_test_launch( + demo_nodes=['temp_sensor'], + fault_manager=False, + ) + + +class TestLoggingApi(GatewayTestCase): + """Communication log endpoint feature tests.""" + + MIN_EXPECTED_APPS = 1 + REQUIRED_APPS = {'temp_sensor'} + + # ------------------------------------------------------------------ + # GET /apps/{id}/logs + # ------------------------------------------------------------------ + + def test_app_get_logs_returns_200(self): + """GET /apps/{app_id}/logs returns 200 with items array. + + # @verifies REQ_INTEROP_061 + """ + data = self.get_json('/apps/temp_sensor/logs') + self.assertIn('items', data) + self.assertIsInstance(data['items'], list) + + def test_app_get_logs_has_items_after_startup(self): + """GET /apps/{app_id}/logs eventually contains log entries. + + /rosout messages from demo node startup populate the ring buffer. + Poll until at least one entry is present. + + # @verifies REQ_INTEROP_061 + """ + data = self.poll_endpoint_until( + '/apps/temp_sensor/logs', + condition=lambda d: d if d.get('items') else None, + timeout=15.0, + ) + items = data['items'] + self.assertGreater(len(items), 0, 'Expected at least one log entry') + + def test_app_log_entry_has_required_fields(self): + """Each log entry has id, timestamp, severity, message, context fields. + + # @verifies REQ_INTEROP_061 + """ + data = self.poll_endpoint_until( + '/apps/temp_sensor/logs', + condition=lambda d: d if d.get('items') else None, + timeout=15.0, + ) + entry = data['items'][0] + self.assertIn('id', entry) + self.assertIn('timestamp', entry) + self.assertIn('severity', entry) + self.assertIn('message', entry) + self.assertIn('context', entry) + # id format: "log_N" + self.assertTrue( + entry['id'].startswith('log_'), + f"id should start with 'log_', got: {entry['id']}" + ) + # timestamp is ISO 8601 with Z suffix + ts = entry['timestamp'] + self.assertTrue( + ts.endswith('Z') and 'T' in ts, + f"timestamp should be ISO 8601 with Z suffix, got: {ts}" + ) + # severity is one of the valid values + self.assertIn( + entry['severity'], + {'debug', 'info', 'warning', 'error', 'fatal'}, + f"unexpected severity: {entry['severity']}" + ) + # context.node is present + self.assertIn('node', entry['context']) + + def test_app_get_logs_severity_filter(self): + """GET /apps/{id}/logs?severity=error returns only entries at error level or above. + + # @verifies REQ_INTEROP_061 + """ + data = self.get_json('/apps/temp_sensor/logs?severity=error') + self.assertIn('items', data) + for entry in data['items']: + self.assertIn( + entry['severity'], + {'error', 'fatal'}, + f"severity filter did not exclude lower levels: {entry['severity']}" + ) + + def test_app_get_logs_invalid_entity_returns_404(self): + """GET /apps/{id}/logs returns 404 for unknown entity. + + # @verifies REQ_INTEROP_061 + """ + self.get_json('/apps/nonexistent_app_xyz/logs', expected_status=404) + + # ------------------------------------------------------------------ + # GET /apps/{id}/logs/configuration + # ------------------------------------------------------------------ + + def test_app_get_logs_configuration_returns_200(self): + """GET /apps/{id}/logs/configuration returns 200 with config fields. + + # @verifies REQ_INTEROP_063 + """ + data = self.get_json('/apps/temp_sensor/logs/configuration') + self.assertIn('severity_filter', data) + self.assertIn('max_entries', data) + + def test_app_get_logs_configuration_defaults(self): + """GET /apps/{id}/logs/configuration returns default values for unconfigured entity. + + # @verifies REQ_INTEROP_063 + """ + data = self.get_json('/apps/temp_sensor/logs/configuration') + self.assertEqual(data['severity_filter'], 'debug') + self.assertGreater(data['max_entries'], 0) + + # ------------------------------------------------------------------ + # PUT /apps/{id}/logs/configuration + # ------------------------------------------------------------------ + + def test_app_put_logs_configuration_updates_severity_filter(self): + """PUT /apps/{id}/logs/configuration returns 204 and update is visible via GET. + + # @verifies REQ_INTEROP_064 + """ + self.put_raw( + '/apps/temp_sensor/logs/configuration', + {'severity_filter': 'warning'}, + expected_status=204, + ) + data = self.get_json('/apps/temp_sensor/logs/configuration') + self.assertEqual(data['severity_filter'], 'warning') + + def test_app_put_logs_configuration_updates_max_entries(self): + """PUT /apps/{id}/logs/configuration returns 204 and update is visible via GET. + + # @verifies REQ_INTEROP_064 + """ + self.put_raw( + '/apps/temp_sensor/logs/configuration', + {'max_entries': 500}, + expected_status=204, + ) + data = self.get_json('/apps/temp_sensor/logs/configuration') + self.assertEqual(data['max_entries'], 500) + + def test_app_put_logs_configuration_invalid_severity_returns_400(self): + """PUT /apps/{id}/logs/configuration returns 400 for invalid severity. + + # @verifies REQ_INTEROP_064 + """ + resp = self.put_raw( + '/apps/temp_sensor/logs/configuration', + {'severity_filter': 'verbose'}, + expected_status=400, + ) + body = resp.json() + self.assertIn('error_code', body) + + def test_app_put_logs_configuration_zero_max_entries_returns_400(self): + """PUT /apps/{id}/logs/configuration returns 400 for max_entries=0. + + # @verifies REQ_INTEROP_064 + """ + resp = self.put_raw( + '/apps/temp_sensor/logs/configuration', + {'max_entries': 0}, + expected_status=400, + ) + body = resp.json() + self.assertIn('error_code', body) + + # ------------------------------------------------------------------ + # GET /components/{id}/logs (prefix match) + # ------------------------------------------------------------------ + + def test_component_get_logs_returns_200(self): + """GET /components/{id}/logs returns 200 with items array. + + # @verifies REQ_INTEROP_061 + """ + components = self.get_json('/components')['items'] + self.assertGreater(len(components), 0, 'At least one component required') + comp_id = components[0]['id'] + + data = self.get_json(f'/components/{comp_id}/logs') + self.assertIn('items', data) + self.assertIsInstance(data['items'], list) + + def test_component_get_logs_configuration_returns_200(self): + """GET /components/{id}/logs/configuration returns 200 with config. + + # @verifies REQ_INTEROP_063 + """ + components = self.get_json('/components')['items'] + self.assertGreater(len(components), 0, 'At least one component required') + comp_id = components[0]['id'] + + data = self.get_json(f'/components/{comp_id}/logs/configuration') + self.assertIn('severity_filter', data) + self.assertIn('max_entries', data) + + # ------------------------------------------------------------------ + # Capability advertisement + # ------------------------------------------------------------------ + + def test_app_detail_includes_logs_capability(self): + """GET /apps/{id} response includes 'logs' in capabilities list. + + # @verifies REQ_INTEROP_061 + """ + data = self.get_json('/apps/temp_sensor') + self.assertIn('capabilities', data) + cap_names = [cap['name'] for cap in data['capabilities']] + self.assertIn('logs', cap_names, f'Expected "logs" in capabilities, got: {cap_names}') + + def test_component_detail_includes_logs_capability(self): + """GET /components/{id} response includes 'logs' in capabilities list. + + # @verifies REQ_INTEROP_061 + """ + components = self.get_json('/components')['items'] + self.assertGreater(len(components), 0, 'At least one component required') + comp_id = components[0]['id'] + + data = self.get_json(f'/components/{comp_id}') + self.assertIn('capabilities', data) + cap_names = [cap['name'] for cap in data['capabilities']] + self.assertIn('logs', cap_names, f'Expected "logs" in capabilities, got: {cap_names}') + + # ------------------------------------------------------------------ + # PUT /components/{id}/logs/configuration + # ------------------------------------------------------------------ + + def test_component_put_logs_configuration_returns_204(self): + """PUT /components/{id}/logs/configuration returns 204 and update is visible via GET. + + # @verifies REQ_INTEROP_064 + """ + components = self.get_json('/components')['items'] + self.assertGreater(len(components), 0, 'At least one component required') + comp_id = components[0]['id'] + + self.put_raw( + f'/components/{comp_id}/logs/configuration', + {'severity_filter': 'info'}, + expected_status=204, + ) + data = self.get_json(f'/components/{comp_id}/logs/configuration') + self.assertEqual(data['severity_filter'], 'info') + + # ------------------------------------------------------------------ + # GET /apps/{id}/logs?context= (context filter) + # ------------------------------------------------------------------ + + def test_app_get_logs_context_filter_nonexistent_returns_empty(self): + """GET /apps/{id}/logs?context= returns empty items list. + + # @verifies REQ_INTEROP_061 + """ + data = self.get_json('/apps/temp_sensor/logs?context=no_such_node_xyzzy_12345') + self.assertIn('items', data) + self.assertIsInstance(data['items'], list) + self.assertEqual( + len(data['items']), 0, + 'Expected empty items for nonexistent context filter' + ) + + # ------------------------------------------------------------------ + # PUT /apps/{id}/logs/configuration โ€” invalid JSON body + # ------------------------------------------------------------------ + + def test_app_put_logs_configuration_invalid_json_returns_400(self): + """PUT /apps/{id}/logs/configuration returns 400 when body is not valid JSON. + + # @verifies REQ_INTEROP_064 + """ + import requests as _requests + response = _requests.put( + f'{self.BASE_URL}/apps/temp_sensor/logs/configuration', + data='not valid json {{{', + headers={'Content-Type': 'application/json'}, + timeout=10, + ) + self.assertEqual(response.status_code, 400) + body = response.json() + self.assertIn('error_code', body) + + # ------------------------------------------------------------------ + # Configured severity_filter acts as a floor + # ------------------------------------------------------------------ + + def test_app_severity_configured_filter_applies_to_get(self): + """After PUT severity_filter=fatal, GET /logs returns only fatal entries. + + The entity-level severity_filter acts as a server-side floor - even + without a query param, entries below the configured threshold are excluded. + + # @verifies REQ_INTEROP_061 + # @verifies REQ_INTEROP_064 + """ + self.put_raw( + '/apps/temp_sensor/logs/configuration', + {'severity_filter': 'fatal'}, + expected_status=204, + ) + # Ensure config is restored even if assertions below fail + self.addCleanup( + self.put_raw, + '/apps/temp_sensor/logs/configuration', + {'severity_filter': 'debug'}, + expected_status=204, + ) + data = self.get_json('/apps/temp_sensor/logs') + for entry in data.get('items', []): + self.assertEqual( + entry['severity'], 'fatal', + f'Expected only fatal entries after setting filter, got: {entry["severity"]}' + ) + + +@launch_testing.post_shutdown_test() +class TestShutdown(unittest.TestCase): + + def test_exit_codes(self, proc_info): + """Check all processes exited cleanly (SIGTERM allowed).""" + for info in proc_info: + self.assertIn( + info.returncode, ALLOWED_EXIT_CODES, + f'{info.process_name} exited with code {info.returncode}' + )