diff --git a/src/ros2_medkit_gateway/CMakeLists.txt b/src/ros2_medkit_gateway/CMakeLists.txt index 7737c39e0..9c220d2e5 100644 --- a/src/ros2_medkit_gateway/CMakeLists.txt +++ b/src/ros2_medkit_gateway/CMakeLists.txt @@ -526,6 +526,10 @@ if(BUILD_TESTING) target_link_libraries(test_plugin_notify_integration gateway_ros2) medkit_set_test_domain(test_plugin_notify_integration) + ament_add_gtest(test_plugin_context_aggregation test/test_plugin_context_aggregation.cpp) + target_link_libraries(test_plugin_context_aggregation gateway_ros2) + medkit_set_test_domain(test_plugin_context_aggregation) + ament_add_gtest(test_auth_manager test/test_auth_manager.cpp) target_link_libraries(test_auth_manager gateway_ros2) @@ -1022,6 +1026,7 @@ if(BUILD_TESTING) test_stream_proxy test_mdns_discovery test_network_utils + test_plugin_context_aggregation ) foreach(_target ${_test_targets}) target_compile_options(${_target} PRIVATE --coverage -O0 -g) diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/core/faults/fault_scope.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/core/faults/fault_scope.hpp new file mode 100644 index 000000000..5d8f24746 --- /dev/null +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/core/faults/fault_scope.hpp @@ -0,0 +1,51 @@ +// 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 "ros2_medkit_gateway/core/models/entity_types.hpp" + +namespace ros2_medkit_gateway { + +class ThreadSafeEntityCache; + +namespace faults { + +/// Resolve the set of App effective-FQNs that fall within an entity's scope by +/// walking the entity cache: +/// - APP: the app's own effective FQN +/// - COMPONENT: every hosted app's FQN +/// - AREA: every app under the area and its (recursive) subareas +/// - FUNCTION: every app hosted directly or via a hosted component +/// Returns an empty set for SERVER / UNKNOWN. +/// +/// Shared by the HTTP fault handlers (`GET /{entity}/faults`) and the ROS 2 +/// plugin-context fault path so both agree on entity -> source-set resolution. +std::set resolve_entity_source_fqns(const ThreadSafeEntityCache & cache, SovdEntityType type, + const std::string & entity_id); + +/// True when `fault` has at least one reporting source and *every* reporting +/// source is within `source_fqns` (exact match or a path-boundary prefix). +/// An empty scope set or an empty/absent source list returns false. +bool fault_in_source_scope(const nlohmann::json & fault, const std::set & source_fqns); + +/// Subset of `faults_array` whose faults satisfy `fault_in_source_scope`. +nlohmann::json filter_faults_by_sources(const nlohmann::json & faults_array, const std::set & source_fqns); + +} // namespace faults +} // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/src/core/faults/fault_scope.cpp b/src/ros2_medkit_gateway/src/core/faults/fault_scope.cpp new file mode 100644 index 000000000..e67560ee1 --- /dev/null +++ b/src/ros2_medkit_gateway/src/core/faults/fault_scope.cpp @@ -0,0 +1,159 @@ +// 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/core/faults/fault_scope.hpp" + +#include +#include + +#include "ros2_medkit_gateway/core/models/thread_safe_entity_cache.hpp" + +namespace ros2_medkit_gateway { +namespace faults { + +namespace { + +void collect_app_fqn(const ThreadSafeEntityCache & cache, const std::string & app_id, std::set & out) { + auto app = cache.get_app(app_id); + if (!app) { + return; + } + auto fqn = app->effective_fqn(); + if (fqn.empty()) { + return; + } + out.insert(std::move(fqn)); +} + +void collect_component_app_fqns(const ThreadSafeEntityCache & cache, const std::string & comp_id, + std::set & out) { + for (const auto & app_id : cache.get_apps_for_component(comp_id)) { + collect_app_fqn(cache, app_id, out); + } +} + +void collect_area_app_fqns(const ThreadSafeEntityCache & cache, const std::string & area_id, + std::set & out) { + // BFS over (area, subareas...) so a top-level area whose components live in + // nested subareas still resolves to the union of every descendant's apps. + // Without the recursion, e.g. `/areas/powertrain/...` returns an empty set + // when components are attached to `engine` (subarea of `powertrain`). + std::vector pending = {area_id}; + std::set visited; + while (!pending.empty()) { + auto current = std::move(pending.back()); + pending.pop_back(); + if (!visited.insert(current).second) { + continue; + } + for (const auto & comp_id : cache.get_components_for_area(current)) { + collect_component_app_fqns(cache, comp_id, out); + } + for (const auto & sub_id : cache.get_subareas(current)) { + pending.push_back(sub_id); + } + } +} + +void collect_function_app_fqns(const ThreadSafeEntityCache & cache, const std::string & function_id, + std::set & out) { + // Function.hosts can contain either App IDs or Component IDs; the indexed + // lookups in the cache only resolve the App-host case (function_to_apps_), + // so we walk the raw `hosts` list and dispatch per host kind ourselves. + auto func = cache.get_function(function_id); + if (!func) { + return; + } + for (const auto & host_id : func->hosts) { + if (cache.get_app(host_id)) { + collect_app_fqn(cache, host_id, out); + } else if (cache.get_component(host_id)) { + collect_component_app_fqns(cache, host_id, out); + } + // Unknown host - silently skip; it would have been flagged by manifest validation. + } +} + +bool source_matches_scope(const std::string & src, const std::set & scope_fqns) { + for (const auto & fqn : scope_fqns) { + if (src == fqn) { + return true; + } + if (src.size() > fqn.size() && src.compare(0, fqn.size(), fqn) == 0 && src[fqn.size()] == '/') { + return true; + } + } + return false; +} + +} // namespace + +std::set resolve_entity_source_fqns(const ThreadSafeEntityCache & cache, SovdEntityType type, + const std::string & entity_id) { + std::set fqns; + switch (type) { + case SovdEntityType::APP: + collect_app_fqn(cache, entity_id, fqns); + break; + case SovdEntityType::COMPONENT: + collect_component_app_fqns(cache, entity_id, fqns); + break; + case SovdEntityType::AREA: + collect_area_app_fqns(cache, entity_id, fqns); + break; + case SovdEntityType::FUNCTION: + collect_function_app_fqns(cache, entity_id, fqns); + break; + case SovdEntityType::SERVER: + case SovdEntityType::UNKNOWN: + break; + } + return fqns; +} + +bool fault_in_source_scope(const nlohmann::json & fault, const std::set & source_fqns) { + if (source_fqns.empty()) { + return false; + } + if (!fault.contains("reporting_sources") || !fault["reporting_sources"].is_array()) { + return false; + } + const auto & sources = fault["reporting_sources"]; + if (sources.empty()) { + return false; + } + for (const auto & src : sources) { + if (!src.is_string()) { + return false; + } + if (!source_matches_scope(src.get(), source_fqns)) { + return false; + } + } + return true; +} + +nlohmann::json filter_faults_by_sources(const nlohmann::json & faults_array, + const std::set & source_fqns) { + nlohmann::json filtered = nlohmann::json::array(); + for (const auto & fault : faults_array) { + if (fault_in_source_scope(fault, source_fqns)) { + filtered.push_back(fault); + } + } + return filtered; +} + +} // namespace faults +} // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/src/http/handlers/fault_handlers.cpp b/src/ros2_medkit_gateway/src/http/handlers/fault_handlers.cpp index 61a87cea5..e38716f5e 100644 --- a/src/ros2_medkit_gateway/src/http/handlers/fault_handlers.cpp +++ b/src/ros2_medkit_gateway/src/http/handlers/fault_handlers.cpp @@ -27,6 +27,7 @@ #include #include "ros2_medkit_gateway/aggregation/aggregation_manager.hpp" +#include "ros2_medkit_gateway/core/faults/fault_scope.hpp" #include "ros2_medkit_gateway/core/http/entity_path_utils.hpp" #include "ros2_medkit_gateway/core/http/error_codes.hpp" #include "ros2_medkit_gateway/core/http/fan_out_helpers.hpp" @@ -106,39 +107,6 @@ tl::expected read_fault_status_filter(const http:: // SOVD-compliant response helpers (legacy free functions kept verbatim) // ============================================================================= -/// Check if a ROS node FQN falls within the entity's source FQN set. -/// -/// A node is in scope iff it equals one of the entity's owned FQNs, OR is a -/// strict path-child of one (i.e., `/<...>`). We deliberately do -/// NOT use raw `rfind(prefix, 0)` because that would let `/ns/node_extra` -/// pass for an entity owning `/ns/node`. Path boundary is enforced by -/// requiring the byte after the prefix to be `/`. -bool source_matches_scope(const std::string & src, const std::set & scope_fqns) { - for (const auto & fqn : scope_fqns) { - if (src == fqn) { - return true; - } - if (src.size() > fqn.size() && src.compare(0, fqn.size(), fqn) == 0 && src[fqn.size()] == '/') { - return true; - } - } - return false; -} - -/// Filter a faults JSON array down to faults whose every reporting source is -/// in the entity's scope. Shares the same all-sources / path-boundary -/// semantics as `FaultHandlers::fault_in_source_scope` so per-entity -/// collection routes and per-fault routes agree on what counts as "in scope". -json filter_faults_by_sources(const json & faults_array, const std::set & source_fqns) { - json filtered = json::array(); - for (const auto & fault : faults_array) { - if (FaultHandlers::fault_in_source_scope(fault, source_fqns)) { - filtered.push_back(fault); - } - } - return filtered; -} - /// Build SOVD status object from fault status string /// Maps ROS 2 medkit status (PREFAILED, PREPASSED, CONFIRMED, HEALED, CLEARED) /// to SOVD aggregated status (active, passive, cleared) @@ -249,25 +217,9 @@ dto::FaultDetailResult wrap_detail_result(json payload) { } // namespace bool FaultHandlers::fault_in_source_scope(const json & fault, const std::set & source_fqns) { - if (source_fqns.empty()) { - return false; - } - if (!fault.contains("reporting_sources") || !fault["reporting_sources"].is_array()) { - return false; - } - const auto & sources = fault["reporting_sources"]; - if (sources.empty()) { - return false; - } - for (const auto & src : sources) { - if (!src.is_string()) { - return false; - } - if (!source_matches_scope(src.get(), source_fqns)) { - return false; - } - } - return true; + // Thin wrapper preserving the public static API; the scope logic now lives in + // the neutral core helper shared with the ROS 2 plugin-context fault path. + return faults::fault_in_source_scope(fault, source_fqns); } // Static method: Build SOVD-compliant fault response from transport-supplied JSON. @@ -553,7 +505,7 @@ http::Result FaultHandlers::list_faults(const http::TypedR const auto & cache = ctx_.node()->get_thread_safe_cache(); auto source_fqns = HandlerContext::resolve_entity_source_fqns(cache, entity_info); - json filtered_faults = filter_faults_by_sources(result.data["faults"], source_fqns); + json filtered_faults = faults::filter_faults_by_sources(result.data["faults"], source_fqns); json response = {{"items", filtered_faults}}; // x-medkit extension (typed DTO) @@ -600,7 +552,7 @@ http::Result FaultHandlers::list_faults(const http::TypedR const auto & cache = ctx_.node()->get_thread_safe_cache(); auto app_fqns = HandlerContext::resolve_entity_source_fqns(cache, entity_info); - json filtered_faults = filter_faults_by_sources(result.data["faults"], app_fqns); + json filtered_faults = faults::filter_faults_by_sources(result.data["faults"], app_fqns); json response = {{"items", filtered_faults}}; dto::FaultListAggXMedkit xm; @@ -639,7 +591,7 @@ http::Result FaultHandlers::list_faults(const http::TypedR json{{"details", result.error_message}, {entity_info.id_field, entity_id}})); } - json filtered_faults = filter_faults_by_sources(result.data["faults"], app_fqns); + json filtered_faults = faults::filter_faults_by_sources(result.data["faults"], app_fqns); json response = {{"items", filtered_faults}}; // x-medkit extension for ros2_medkit-specific fields (typed DTO) @@ -981,7 +933,7 @@ http::Result FaultHandlers::clear_all_faults(const http::TypedR } const auto & cache = ctx_.node()->get_thread_safe_cache(); auto entity_fqns = HandlerContext::resolve_entity_source_fqns(cache, entity_info); - json faults_to_clear = filter_faults_by_sources(result.data["faults"], entity_fqns); + json faults_to_clear = faults::filter_faults_by_sources(result.data["faults"], entity_fqns); // Clear each matching fault. Use `skip_correlation_auto_clear=true` for // the same reason as the single-fault DELETE: keep this entity's clear diff --git a/src/ros2_medkit_gateway/src/http/handlers/handler_context.cpp b/src/ros2_medkit_gateway/src/http/handlers/handler_context.cpp index e21a2879d..6a2929578 100644 --- a/src/ros2_medkit_gateway/src/http/handlers/handler_context.cpp +++ b/src/ros2_medkit_gateway/src/http/handlers/handler_context.cpp @@ -18,6 +18,7 @@ #include "ros2_medkit_gateway/aggregation/aggregation_manager.hpp" #include "ros2_medkit_gateway/core/entity_validation.hpp" +#include "ros2_medkit_gateway/core/faults/fault_scope.hpp" #include "ros2_medkit_gateway/core/http/error_codes.hpp" #include "ros2_medkit_gateway/core/managers/lock_manager.hpp" #include "ros2_medkit_gateway/core/models/entity_capabilities.hpp" @@ -354,91 +355,28 @@ bool HandlerContext::is_origin_allowed(const std::string & origin) const { return false; } -namespace { - -void collect_app_fqn(const ThreadSafeEntityCache & cache, const std::string & app_id, std::set & out) { - auto app = cache.get_app(app_id); - if (!app) { - return; - } - auto fqn = app->effective_fqn(); - if (fqn.empty()) { - return; - } - out.insert(std::move(fqn)); -} - -void collect_component_app_fqns(const ThreadSafeEntityCache & cache, const std::string & comp_id, - std::set & out) { - for (const auto & app_id : cache.get_apps_for_component(comp_id)) { - collect_app_fqn(cache, app_id, out); - } -} - -void collect_area_app_fqns(const ThreadSafeEntityCache & cache, const std::string & area_id, - std::set & out) { - // BFS over (area, subareas...) so a top-level area whose components live in - // nested subareas still resolves to the union of every descendant's apps. - // Without the recursion, e.g. `/areas/powertrain/...` returns an empty set - // when components are attached to `engine` (subarea of `powertrain`). - std::vector pending = {area_id}; - std::set visited; - while (!pending.empty()) { - auto current = std::move(pending.back()); - pending.pop_back(); - if (!visited.insert(current).second) { - continue; - } - for (const auto & comp_id : cache.get_components_for_area(current)) { - collect_component_app_fqns(cache, comp_id, out); - } - for (const auto & sub_id : cache.get_subareas(current)) { - pending.push_back(sub_id); - } - } -} - -void collect_function_app_fqns(const ThreadSafeEntityCache & cache, const std::string & function_id, - std::set & out) { - // Function.hosts can contain either App IDs or Component IDs; the indexed - // lookups in the cache only resolve the App-host case (function_to_apps_), - // so we walk the raw `hosts` list and dispatch per host kind ourselves. - auto func = cache.get_function(function_id); - if (!func) { - return; - } - for (const auto & host_id : func->hosts) { - if (cache.get_app(host_id)) { - collect_app_fqn(cache, host_id, out); - } else if (cache.get_component(host_id)) { - collect_component_app_fqns(cache, host_id, out); - } - // Unknown host - silently skip; it would have been flagged by manifest validation. - } -} - -} // namespace - std::set HandlerContext::resolve_entity_source_fqns(const ThreadSafeEntityCache & cache, const EntityInfo & entity) { - std::set fqns; + // Delegate to the neutral core helper so the HTTP fault handlers and the + // ROS 2 plugin-context fault path share one entity -> source-FQN resolution. + SovdEntityType type = SovdEntityType::UNKNOWN; switch (entity.type) { case EntityType::APP: - collect_app_fqn(cache, entity.id, fqns); + type = SovdEntityType::APP; break; case EntityType::COMPONENT: - collect_component_app_fqns(cache, entity.id, fqns); + type = SovdEntityType::COMPONENT; break; case EntityType::AREA: - collect_area_app_fqns(cache, entity.id, fqns); + type = SovdEntityType::AREA; break; case EntityType::FUNCTION: - collect_function_app_fqns(cache, entity.id, fqns); + type = SovdEntityType::FUNCTION; break; case EntityType::UNKNOWN: break; } - return fqns; + return faults::resolve_entity_source_fqns(cache, type, entity.id); } std::vector HandlerContext::resolve_app_host_fqns(const ThreadSafeEntityCache & cache, diff --git a/src/ros2_medkit_gateway/src/plugins/plugin_context.cpp b/src/ros2_medkit_gateway/src/plugins/plugin_context.cpp index 08279cbb4..4cec62393 100644 --- a/src/ros2_medkit_gateway/src/plugins/plugin_context.cpp +++ b/src/ros2_medkit_gateway/src/plugins/plugin_context.cpp @@ -16,9 +16,12 @@ #include #include +#include #include +#include "ros2_medkit_gateway/aggregation/aggregation_manager.hpp" #include "ros2_medkit_gateway/core/entity_validation.hpp" +#include "ros2_medkit_gateway/core/faults/fault_scope.hpp" #include "ros2_medkit_gateway/core/condition_evaluator.hpp" #include "ros2_medkit_gateway/core/http/error_codes.hpp" @@ -31,6 +34,29 @@ namespace ros2_medkit_gateway { +namespace { + +/// Map a SovdEntityType to the plural URL path segment used in the REST API. +/// Returns empty string for SERVER/UNKNOWN (no faults collection on those). +std::string entity_type_to_url_segment(SovdEntityType type) { + switch (type) { + case SovdEntityType::APP: + return "apps"; + case SovdEntityType::COMPONENT: + return "components"; + case SovdEntityType::AREA: + return "areas"; + case SovdEntityType::FUNCTION: + return "functions"; + case SovdEntityType::SERVER: + case SovdEntityType::UNKNOWN: + return ""; + } + return ""; +} + +} // namespace + // ---- Concrete implementation ---- class GatewayPluginContext : public RosPluginContext { @@ -76,28 +102,53 @@ class GatewayPluginContext : public RosPluginContext { } nlohmann::json list_entity_faults(const std::string & entity_id) const override { - if (!fault_manager_ || !fault_manager_->is_available()) { - return nlohmann::json::array(); - } - - // Determine source_id for fault filtering based on entity type + // Determine entity type (needed for both local query and peer path construction). auto entity = get_entity(entity_id); if (!entity) { return nlohmann::json::array(); } - std::string source_id; - if (entity->type == SovdEntityType::COMPONENT) { - source_id = entity->namespace_path; - } else if (entity->type == SovdEntityType::APP) { - source_id = entity->fqn; + nlohmann::json local_faults = nlohmann::json::array(); + + if (fault_manager_ && fault_manager_->is_available()) { + // Mirror the HTTP per-entity fault handler: fetch all faults, then scope + // them to the entity's resolved App-FQN set (APP -> itself, COMPONENT -> + // hosted apps, AREA -> descendant apps, FUNCTION -> host apps) via the + // shared core helper. The fault manager returns a {"faults": [...]} + // object; this method's contract is a bare array, so extract and filter + // the inner array. + auto result = fault_manager_->list_faults(""); + if (result.success && result.data.contains("faults") && result.data["faults"].is_array()) { + const auto & cache = node_->get_thread_safe_cache(); + const auto source_fqns = faults::resolve_entity_source_fqns(cache, entity->type, entity_id); + local_faults = faults::filter_faults_by_sources(result.data["faults"], source_fqns); + } } - auto result = fault_manager_->list_faults(source_id); - if (result.success && result.data.is_array()) { - return result.data; + // Fan-out to peer gateways: fetch faults for this entity from each peer. + // The peer path mirrors the HTTP REST route: /api/v1///faults. + // Auth: the ROS 2 service path has no inbound HTTP Authorization header to + // forward, so peers are queried with an empty credential - fan-out over this + // path only surfaces faults from peers that do not gate their /faults route. + auto * agg = node_->get_aggregation_manager(); + if (agg) { + const std::string type_segment = entity_type_to_url_segment(entity->type); + if (!type_segment.empty()) { + const std::string peer_path = "/api/v1/" + type_segment + "/" + entity_id + "/faults"; + auto fan_result = agg->fan_out_get(peer_path, ""); + if (fan_result.merged_items.is_array()) { + for (const auto & item : fan_result.merged_items) { + local_faults.push_back(item); + } + } + if (fan_result.is_partial) { + RCLCPP_WARN(node_->get_logger(), "list_entity_faults('%s'): partial peer fan-out, %zu peer(s) failed", + entity_id.c_str(), fan_result.failed_peers.size()); + } + } } - return nlohmann::json::array(); + + return local_faults; } std::optional validate_entity_for_route(const PluginRequest & req, PluginResponse & res, @@ -207,14 +258,43 @@ class GatewayPluginContext : public RosPluginContext { } nlohmann::json list_all_faults() const override { - if (!fault_manager_ || !fault_manager_->is_available()) { - return nlohmann::json::object(); + nlohmann::json response = nlohmann::json::object(); + + if (fault_manager_ && fault_manager_->is_available()) { + auto result = fault_manager_->list_faults(""); + if (result.success) { + response = result.data; + } } - auto result = fault_manager_->list_faults(""); - if (result.success) { - return result.data; + + // Fan-out to peer gateways: fetch all faults from /api/v1/faults on each peer. + // Auth: see list_entity_faults - the ROS 2 service path forwards no inbound + // Authorization header, so peers are queried with an empty credential. + auto * agg = node_->get_aggregation_manager(); + if (agg) { + auto fan_result = agg->fan_out_get("/api/v1/faults", ""); + if (fan_result.merged_items.is_array()) { + // Ensure local response has a "faults" array to append to. + if (!response.contains("faults") || !response["faults"].is_array()) { + response["faults"] = nlohmann::json::array(); + } + for (const auto & item : fan_result.merged_items) { + response["faults"].push_back(item); + } + } + if (fan_result.is_partial) { + RCLCPP_WARN(node_->get_logger(), "list_all_faults: partial peer fan-out, %zu peer(s) failed", + fan_result.failed_peers.size()); + } + } + + // "count" comes from the local-only query; after merging peer faults it + // would undercount, so keep it consistent with the merged array. + if (response.contains("count") && response.contains("faults") && response["faults"].is_array()) { + response["count"] = response["faults"].size(); } - return nlohmann::json::object(); + + return response; } void register_sampler( diff --git a/src/ros2_medkit_gateway/test/test_plugin_context_aggregation.cpp b/src/ros2_medkit_gateway/test/test_plugin_context_aggregation.cpp new file mode 100644 index 000000000..afaf0640c --- /dev/null +++ b/src/ros2_medkit_gateway/test/test_plugin_context_aggregation.cpp @@ -0,0 +1,742 @@ +// 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. + +// Tests for plugin_context.cpp aggregation fan-out in: +// - list_entity_faults (peers queried via /api/v1///faults) +// - list_all_faults (peers queried via /api/v1/faults) +// - get_entity_snapshot (peer entities already in cache from discovery refresh) + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "ros2_medkit_gateway/aggregation/aggregation_manager.hpp" +#include "ros2_medkit_gateway/core/managers/fault_manager.hpp" +#include "ros2_medkit_gateway/core/transports/fault_service_transport.hpp" +#include "ros2_medkit_gateway/gateway_node.hpp" +#include "ros2_medkit_gateway/plugins/ros_plugin_context.hpp" + +using json = nlohmann::json; +using ros2_medkit_gateway::GatewayNode; + +namespace { + +// --------------------------------------------------------------------------- +// Port / temp manifest helpers (same pattern as test_plugin_notify_integration) +// --------------------------------------------------------------------------- + +int reserve_local_port() { + int sock = socket(AF_INET, SOCK_STREAM, 0); + if (sock < 0) { + ADD_FAILURE() << "socket() failed: " << std::strerror(errno); + return 0; + } + sockaddr_in addr{}; + addr.sin_family = AF_INET; + addr.sin_addr.s_addr = htonl(INADDR_LOOPBACK); + addr.sin_port = 0; + if (bind(sock, reinterpret_cast(&addr), sizeof(addr)) != 0) { + ADD_FAILURE() << "bind() failed: " << std::strerror(errno); + close(sock); + return 0; + } + socklen_t len = sizeof(addr); + getsockname(sock, reinterpret_cast(&addr), &len); + int port = ntohs(addr.sin_port); + close(sock); + return port; +} + +// Write a temp manifest file; returns the path. +std::string write_temp_manifest(const std::string & contents) { + char tmpl[] = "/tmp/ros2_medkit_plugin_ctx_agg_XXXXXX.yaml"; + int fd = mkstemps(tmpl, 5); + if (fd < 0) { + ADD_FAILURE() << "mkstemps() failed: " << std::strerror(errno); + return {}; + } + close(fd); + std::ofstream out(tmpl); + out << contents; + return tmpl; +} + +// --------------------------------------------------------------------------- +// RAII mock HTTP peer server (same pattern as test_aggregation_manager) +// --------------------------------------------------------------------------- + +class MockPeerServer { + public: + MockPeerServer() = default; + + ~MockPeerServer() { + if (server_) { + server_->stop(); + } + if (thread_.joinable()) { + thread_.join(); + } + } + + MockPeerServer(const MockPeerServer &) = delete; + MockPeerServer & operator=(const MockPeerServer &) = delete; + MockPeerServer(MockPeerServer &&) = delete; + MockPeerServer & operator=(MockPeerServer &&) = delete; + + httplib::Server & server() { + if (!server_) { + server_ = std::make_unique(); + } + return *server_; + } + + int start() { + server(); // ensure server_ is constructed even if start() is called before server() + port_ = server_->bind_to_any_port("127.0.0.1"); + thread_ = std::thread([this]() { + server_->listen_after_bind(); + }); + return port_; + } + + std::string url() const { + return "http://127.0.0.1:" + std::to_string(port_); + } + + private: + std::unique_ptr server_; + std::thread thread_; + int port_{0}; +}; + +// --------------------------------------------------------------------------- +// Offline fake fault transport - lets tests exercise the LOCAL fault path of +// list_entity_faults / list_all_faults without a live ros2_medkit_fault_manager. +// Returns the same {"faults":[...], "count":N} envelope shape as the real +// Ros2FaultServiceTransport. The plugin context always queries with an empty +// source_id and scopes locally, so the full set is returned regardless. +// --------------------------------------------------------------------------- + +class FakeFaultTransport : public ros2_medkit_gateway::FaultServiceTransport { + public: + explicit FakeFaultTransport(json faults) : faults_(std::move(faults)) { + } + + ros2_medkit_gateway::FaultResult list_faults(const std::string & /*source_id*/, bool /*include_prefailed*/, + bool /*include_confirmed*/, bool /*include_cleared*/, + bool /*include_healed*/, bool /*include_muted*/, + bool /*include_clusters*/) override { + ros2_medkit_gateway::FaultResult r; + r.success = true; + r.data = {{"faults", faults_}, {"count", faults_.size()}}; + return r; + } + + bool is_available() const override { + return true; + } + + // Unused by these tests - return benign failures. + ros2_medkit_gateway::FaultResult report_fault(const std::string & /*fault_code*/, uint8_t /*severity*/, + const std::string & /*description*/, + const std::string & /*source_id*/) override { + return {false, json::object(), "not implemented"}; + } + ros2_medkit_gateway::FaultWithEnvJsonResult get_fault_with_env(const std::string & /*fault_code*/, + const std::string & /*source_id*/) override { + return {false, "not implemented", json::object()}; + } + ros2_medkit_gateway::FaultResult get_fault(const std::string & /*fault_code*/, + const std::string & /*source_id*/) override { + return {false, json::object(), "not implemented"}; + } + ros2_medkit_gateway::FaultResult clear_fault(const std::string & /*fault_code*/, + bool /*skip_correlation_auto_clear*/) override { + return {false, json::object(), "not implemented"}; + } + ros2_medkit_gateway::FaultResult get_snapshots(const std::string & /*fault_code*/, + const std::string & /*topic*/) override { + return {false, json::object(), "not implemented"}; + } + ros2_medkit_gateway::FaultResult get_rosbag(const std::string & /*fault_code*/) override { + return {false, json::object(), "not implemented"}; + } + ros2_medkit_gateway::FaultResult list_rosbags(const std::string & /*entity_fqn*/) override { + return {false, json::object(), "not implemented"}; + } + bool wait_for_services(std::chrono::duration /*timeout*/) override { + return true; + } + + private: + json faults_; +}; + +// Two canned faults: one reported by the manifest app "brakes" (/vehicle/brakes), +// one by an unrelated node (/other/sensor) used to prove entity scoping excludes +// out-of-scope faults. +json make_local_faults() { + return json::array({ + {{"fault_code", "LOCAL_BRAKE_FAULT"}, + {"description", "Local brake fault"}, + {"status", "ACTIVE"}, + {"reporting_sources", json::array({"/vehicle/brakes"})}}, + {{"fault_code", "OTHER_NODE_FAULT"}, + {"description", "Fault from an unrelated node"}, + {"status", "ACTIVE"}, + {"reporting_sources", json::array({"/other/sensor"})}}, + }); +} + +// --------------------------------------------------------------------------- +// Base manifest with one component ("brakes_ecu") + one app ("brakes") +// --------------------------------------------------------------------------- + +constexpr const char * kManifest = R"( +manifest_version: "1.0" +metadata: + name: plugin-ctx-agg-test + version: "0.0.1" +areas: + - id: vehicle + name: Vehicle +components: + - id: brakes_ecu + name: Brakes ECU + area: vehicle +apps: + - id: brakes + name: Brakes + is_located_on: brakes_ecu + ros_binding: + node_name: brakes + namespace: /vehicle +functions: + - id: braking + name: Braking + hosts: + - brakes +)"; + +// --------------------------------------------------------------------------- +// Fixture: GatewayNode without aggregation (local-only behavior) +// --------------------------------------------------------------------------- + +class PluginContextNoAggTest : public ::testing::Test { + protected: + static void SetUpTestSuite() { + if (!rclcpp::ok()) { + rclcpp::init(0, nullptr); + } + } + + static void TearDownTestSuite() { + if (rclcpp::ok()) { + rclcpp::shutdown(); + } + } + + void SetUp() override { + manifest_path_ = write_temp_manifest(kManifest); + ASSERT_FALSE(manifest_path_.empty()); + + const int port = reserve_local_port(); + ASSERT_GT(port, 0); + + rclcpp::NodeOptions opts; + opts.parameter_overrides({ + {"discovery.mode", "manifest_only"}, + {"discovery.manifest_path", manifest_path_}, + {"discovery.manifest_strict_validation", false}, + {"discovery.runtime.enabled", false}, + {"discovery.runtime.default_component.enabled", false}, + {"server.host", std::string("127.0.0.1")}, + {"server.port", port}, + // No aggregation.enabled -> get_aggregation_manager() returns nullptr + }); + node_ = std::make_shared(opts); + } + + void TearDown() override { + node_.reset(); + if (!manifest_path_.empty()) { + std::remove(manifest_path_.c_str()); + } + } + + std::shared_ptr node_; + std::string manifest_path_; +}; + +// --------------------------------------------------------------------------- +// Fixture: GatewayNode with aggregation enabled, mock peer provides faults +// --------------------------------------------------------------------------- + +class PluginContextWithPeerTest : public ::testing::Test { + protected: + static void SetUpTestSuite() { + if (!rclcpp::ok()) { + rclcpp::init(0, nullptr); + } + } + + static void TearDownTestSuite() { + if (rclcpp::ok()) { + rclcpp::shutdown(); + } + } + + void SetUp() override { + manifest_path_ = write_temp_manifest(kManifest); + ASSERT_FALSE(manifest_path_.empty()); + + // Install fault endpoints on the mock peer. + // /api/v1/health - required for peer health check + mock_.server().Get("/api/v1/health", [](const httplib::Request &, httplib::Response & res) { + res.set_content(R"({"status":"healthy"})", "application/json"); + }); + + // /api/v1/apps/brakes/faults - returns a PROTECTIVE_STOP fault + mock_.server().Get(R"(/api/v1/apps/brakes/faults)", [](const httplib::Request &, httplib::Response & res) { + json item = { + {"fault_code", "PROTECTIVE_STOP"}, {"description", "Emergency stop triggered"}, {"status", "ACTIVE"}}; + res.set_content(json({{"items", json::array({item})}}).dump(), "application/json"); + }); + + // /api/v1/faults - global faults list (items array) + mock_.server().Get("/api/v1/faults", [](const httplib::Request &, httplib::Response & res) { + json item = {{"fault_code", "PEER_FAULT"}, {"description", "Fault from peer"}, {"status", "ACTIVE"}}; + res.set_content(json({{"items", json::array({item})}}).dump(), "application/json"); + }); + + // Discovery endpoints (empty) - needed during GatewayNode startup discovery refresh + mock_.server().Get("/api/v1/components", [](const httplib::Request &, httplib::Response & res) { + res.set_content(R"({"items":[]})", "application/json"); + }); + mock_.server().Get("/api/v1/areas", [](const httplib::Request &, httplib::Response & res) { + res.set_content(R"({"items":[]})", "application/json"); + }); + mock_.server().Get("/api/v1/apps", [](const httplib::Request &, httplib::Response & res) { + res.set_content(R"({"items":[]})", "application/json"); + }); + mock_.server().Get("/api/v1/functions", [](const httplib::Request &, httplib::Response & res) { + res.set_content(R"({"items":[]})", "application/json"); + }); + + int peer_port = mock_.start(); + ASSERT_GT(peer_port, 0); + peer_url_ = mock_.url(); + + const int gw_port = reserve_local_port(); + ASSERT_GT(gw_port, 0); + + // Configure the GatewayNode with aggregation pointing at the mock peer. + // Static peers use parallel arrays: aggregation.peer_urls / aggregation.peer_names. + rclcpp::NodeOptions opts; + opts.parameter_overrides({ + {"discovery.mode", "manifest_only"}, + {"discovery.manifest_path", manifest_path_}, + {"discovery.manifest_strict_validation", false}, + {"discovery.runtime.enabled", false}, + {"discovery.runtime.default_component.enabled", false}, + {"server.host", std::string("127.0.0.1")}, + {"server.port", gw_port}, + {"aggregation.enabled", true}, + {"aggregation.timeout_ms", static_cast(5000)}, + {"aggregation.peer_urls", std::vector{peer_url_}}, + {"aggregation.peer_names", std::vector{"mock_peer"}}, + }); + node_ = std::make_shared(opts); + + // Make the peer healthy so fan-out actually sends requests to it. + auto * agg = node_->get_aggregation_manager(); + ASSERT_NE(agg, nullptr) << "AggregationManager must be non-null when aggregation.enabled=true"; + agg->check_all_health(); + ASSERT_EQ(agg->healthy_peer_count(), 1u) << "mock peer must be healthy for fan-out to work"; + } + + void TearDown() override { + node_.reset(); + if (!manifest_path_.empty()) { + std::remove(manifest_path_.c_str()); + } + } + + std::shared_ptr node_; + MockPeerServer mock_; + std::string manifest_path_; + std::string peer_url_; +}; + +// --------------------------------------------------------------------------- +// Fixture: aggregation enabled, peer is healthy at /health but FAILS every +// fault request (503). Exercises the partial-fan-out path - the peer +// contributes nothing and local faults must still be returned. +// --------------------------------------------------------------------------- + +class PluginContextFailingPeerTest : public ::testing::Test { + protected: + static void SetUpTestSuite() { + if (!rclcpp::ok()) { + rclcpp::init(0, nullptr); + } + } + + static void TearDownTestSuite() { + if (rclcpp::ok()) { + rclcpp::shutdown(); + } + } + + void SetUp() override { + manifest_path_ = write_temp_manifest(kManifest); + ASSERT_FALSE(manifest_path_.empty()); + + mock_.server().Get("/api/v1/health", [](const httplib::Request &, httplib::Response & res) { + res.set_content(R"({"status":"healthy"})", "application/json"); + }); + + // Every fault query 503s, so fan-out marks the peer failed (is_partial). + auto fail = [](const httplib::Request &, httplib::Response & res) { + res.status = 503; + res.set_content(R"({"error":"unavailable"})", "application/json"); + }; + mock_.server().Get(R"(/api/v1/apps/brakes/faults)", fail); + mock_.server().Get("/api/v1/faults", fail); + + // Discovery endpoints (empty) - needed during GatewayNode startup discovery refresh + auto empty_items = [](const httplib::Request &, httplib::Response & res) { + res.set_content(R"({"items":[]})", "application/json"); + }; + mock_.server().Get("/api/v1/components", empty_items); + mock_.server().Get("/api/v1/areas", empty_items); + mock_.server().Get("/api/v1/apps", empty_items); + mock_.server().Get("/api/v1/functions", empty_items); + + int peer_port = mock_.start(); + ASSERT_GT(peer_port, 0); + peer_url_ = mock_.url(); + + const int gw_port = reserve_local_port(); + ASSERT_GT(gw_port, 0); + + rclcpp::NodeOptions opts; + opts.parameter_overrides({ + {"discovery.mode", "manifest_only"}, + {"discovery.manifest_path", manifest_path_}, + {"discovery.manifest_strict_validation", false}, + {"discovery.runtime.enabled", false}, + {"discovery.runtime.default_component.enabled", false}, + {"server.host", std::string("127.0.0.1")}, + {"server.port", gw_port}, + {"aggregation.enabled", true}, + {"aggregation.timeout_ms", static_cast(5000)}, + {"aggregation.peer_urls", std::vector{peer_url_}}, + {"aggregation.peer_names", std::vector{"failing_peer"}}, + }); + node_ = std::make_shared(opts); + + auto * agg = node_->get_aggregation_manager(); + ASSERT_NE(agg, nullptr); + agg->check_all_health(); + ASSERT_EQ(agg->healthy_peer_count(), 1u) << "peer must pass /health so the fault request reaches it and 503s"; + } + + void TearDown() override { + node_.reset(); + if (!manifest_path_.empty()) { + std::remove(manifest_path_.c_str()); + } + } + + std::shared_ptr node_; + MockPeerServer mock_; + std::string manifest_path_; + std::string peer_url_; +}; + +} // namespace + +// ============================================================================= +// Tests: no aggregation manager (nullptr) - local-only behavior unchanged +// ============================================================================= + +TEST_F(PluginContextNoAggTest, ListEntityFaultsNoAgg_ReturnsEmptyArrayWithoutFaultManager) { + // Fault manager is null, no aggregation. Result: empty array. + auto ctx = ros2_medkit_gateway::make_gateway_plugin_context(node_.get(), nullptr, nullptr); + ASSERT_NE(ctx, nullptr); + + auto faults = ctx->list_entity_faults("brakes"); + EXPECT_TRUE(faults.is_array()); + EXPECT_EQ(faults.size(), 0u); +} + +TEST_F(PluginContextNoAggTest, ListAllFaultsNoAgg_ReturnsEmptyObjectWithoutFaultManager) { + auto ctx = ros2_medkit_gateway::make_gateway_plugin_context(node_.get(), nullptr, nullptr); + ASSERT_NE(ctx, nullptr); + + auto result = ctx->list_all_faults(); + // No fault manager, no aggregation -> empty object with no "faults" key + EXPECT_TRUE(result.is_object()); + EXPECT_FALSE(result.contains("faults")); +} + +TEST_F(PluginContextNoAggTest, GetEntitySnapshot_ContainsManifestEntities) { + auto ctx = ros2_medkit_gateway::make_gateway_plugin_context(node_.get(), nullptr, nullptr); + ASSERT_NE(ctx, nullptr); + + auto snapshot = ctx->get_entity_snapshot(); + + bool found_area = false; + for (const auto & a : snapshot.areas) { + if (a.id == "vehicle") { + found_area = true; + } + } + EXPECT_TRUE(found_area) << "area 'vehicle' should be in snapshot"; + + bool found_comp = false; + for (const auto & c : snapshot.components) { + if (c.id == "brakes_ecu") { + found_comp = true; + } + } + EXPECT_TRUE(found_comp) << "component 'brakes_ecu' should be in snapshot"; + + bool found_app = false; + for (const auto & a : snapshot.apps) { + if (a.id == "brakes") { + found_app = true; + } + } + EXPECT_TRUE(found_app) << "app 'brakes' should be in snapshot"; +} + +TEST_F(PluginContextNoAggTest, ListEntityFaultsNoAgg_UnknownEntityReturnsEmpty) { + auto ctx = ros2_medkit_gateway::make_gateway_plugin_context(node_.get(), nullptr, nullptr); + ASSERT_NE(ctx, nullptr); + + // "nonexistent" is not in the manifest -> empty array + auto faults = ctx->list_entity_faults("nonexistent"); + EXPECT_TRUE(faults.is_array()); + EXPECT_EQ(faults.size(), 0u); +} + +// ============================================================================= +// Tests: with aggregation enabled and a live mock peer +// ============================================================================= + +// @verifies REQ_INTEROP_013 +TEST_F(PluginContextWithPeerTest, ListEntityFaults_IncludesPeerFault) { + auto ctx = ros2_medkit_gateway::make_gateway_plugin_context(node_.get(), nullptr, nullptr); + ASSERT_NE(ctx, nullptr); + + // "brakes" is in the local manifest. No local fault manager (null), but the + // peer returns a PROTECTIVE_STOP fault via /api/v1/apps/brakes/faults. + auto faults = ctx->list_entity_faults("brakes"); + + ASSERT_TRUE(faults.is_array()); + ASSERT_GE(faults.size(), 1u) << "peer fault should be included in the result"; + + bool found_peer_fault = false; + for (const auto & f : faults) { + if (f.contains("fault_code") && f["fault_code"] == "PROTECTIVE_STOP") { + found_peer_fault = true; + } + } + EXPECT_TRUE(found_peer_fault) << "PROTECTIVE_STOP fault from peer not found in list_entity_faults result"; +} + +// @verifies REQ_INTEROP_013 +TEST_F(PluginContextWithPeerTest, ListAllFaults_IncludesPeerFault) { + auto ctx = ros2_medkit_gateway::make_gateway_plugin_context(node_.get(), nullptr, nullptr); + ASSERT_NE(ctx, nullptr); + + // No local fault manager (null). Peer returns PEER_FAULT via /api/v1/faults. + auto result = ctx->list_all_faults(); + + // The fan-out appends peer items to the "faults" key. + ASSERT_TRUE(result.is_object()); + ASSERT_TRUE(result.contains("faults")) << "list_all_faults result must have 'faults' key when peer provides faults"; + ASSERT_TRUE(result["faults"].is_array()); + ASSERT_GE(result["faults"].size(), 1u) << "peer fault should be in 'faults' array"; + + bool found_peer_fault = false; + for (const auto & f : result["faults"]) { + if (f.contains("fault_code") && f["fault_code"] == "PEER_FAULT") { + found_peer_fault = true; + } + } + EXPECT_TRUE(found_peer_fault) << "PEER_FAULT from peer not found in list_all_faults result"; +} + +TEST_F(PluginContextWithPeerTest, GetEntitySnapshot_ContainsLocalManifestEntities) { + auto ctx = ros2_medkit_gateway::make_gateway_plugin_context(node_.get(), nullptr, nullptr); + ASSERT_NE(ctx, nullptr); + + // Snapshot comes from the entity cache which is populated from the manifest + // (and merged with peer entities during discovery refresh). + // At minimum, local manifest entities must be present. + auto snapshot = ctx->get_entity_snapshot(); + + bool found_app = false; + for (const auto & a : snapshot.apps) { + if (a.id == "brakes") { + found_app = true; + } + } + EXPECT_TRUE(found_app) << "local app 'brakes' should be in snapshot even with aggregation enabled"; +} + +// ============================================================================= +// Tests: LOCAL fault path with a real FaultManager (fake transport, no peers). +// These exercise the branch that list_*Faults take when fault_manager_ != null, +// which the nullptr-fault-manager tests above never reach. +// ============================================================================= + +namespace { +bool contains_fault_code(const json & arr, const std::string & code) { + for (const auto & f : arr) { + if (f.contains("fault_code") && f["fault_code"] == code) { + return true; + } + } + return false; +} +} // namespace + +// @verifies REQ_INTEROP_013 +TEST_F(PluginContextNoAggTest, ListEntityFaults_LocalFaultManager_IncludesScopedFaultOnly) { + ros2_medkit_gateway::FaultManager fm(std::make_shared(make_local_faults())); + auto ctx = ros2_medkit_gateway::make_gateway_plugin_context(node_.get(), &fm, nullptr); + ASSERT_NE(ctx, nullptr); + + // App "brakes" resolves to /vehicle/brakes. The local fault reported by that + // node must be present; the out-of-scope /other/sensor fault must NOT be. + auto faults = ctx->list_entity_faults("brakes"); + ASSERT_TRUE(faults.is_array()); + EXPECT_TRUE(contains_fault_code(faults, "LOCAL_BRAKE_FAULT")) + << "local fault for app 'brakes' must be returned (regression guard for the .data shape bug)"; + EXPECT_FALSE(contains_fault_code(faults, "OTHER_NODE_FAULT")) + << "fault from /other/sensor must be scoped out of app 'brakes'"; +} + +// @verifies REQ_INTEROP_013 +TEST_F(PluginContextNoAggTest, ListEntityFaults_AreaResolvesToDescendantApps) { + ros2_medkit_gateway::FaultManager fm(std::make_shared(make_local_faults())); + auto ctx = ros2_medkit_gateway::make_gateway_plugin_context(node_.get(), &fm, nullptr); + ASSERT_NE(ctx, nullptr); + + // Area "vehicle" -> component "brakes_ecu" -> app "brakes" (/vehicle/brakes). + // The brakes fault must surface for the area; /other/sensor must not leak in. + auto faults = ctx->list_entity_faults("vehicle"); + ASSERT_TRUE(faults.is_array()); + EXPECT_TRUE(contains_fault_code(faults, "LOCAL_BRAKE_FAULT")) + << "area 'vehicle' must aggregate faults from its descendant app 'brakes'"; + EXPECT_FALSE(contains_fault_code(faults, "OTHER_NODE_FAULT")) + << "out-of-area fault from /other/sensor must not leak into area 'vehicle'"; +} + +// @verifies REQ_INTEROP_013 +TEST_F(PluginContextWithPeerTest, ListEntityFaults_MergesLocalAndPeerFaults) { + ros2_medkit_gateway::FaultManager fm(std::make_shared(make_local_faults())); + auto ctx = ros2_medkit_gateway::make_gateway_plugin_context(node_.get(), &fm, nullptr); + ASSERT_NE(ctx, nullptr); + + // Local /vehicle/brakes fault AND the peer's PROTECTIVE_STOP must both appear. + auto faults = ctx->list_entity_faults("brakes"); + ASSERT_TRUE(faults.is_array()); + EXPECT_TRUE(contains_fault_code(faults, "LOCAL_BRAKE_FAULT")) << "local fault missing from merged result"; + EXPECT_TRUE(contains_fault_code(faults, "PROTECTIVE_STOP")) << "peer fault missing from merged result"; +} + +// @verifies REQ_INTEROP_013 +TEST_F(PluginContextWithPeerTest, ListAllFaults_MergesLocalAndPeerFaults) { + ros2_medkit_gateway::FaultManager fm(std::make_shared(make_local_faults())); + auto ctx = ros2_medkit_gateway::make_gateway_plugin_context(node_.get(), &fm, nullptr); + ASSERT_NE(ctx, nullptr); + + auto result = ctx->list_all_faults(); + ASSERT_TRUE(result.is_object()); + ASSERT_TRUE(result.contains("faults")); + ASSERT_TRUE(result["faults"].is_array()); + EXPECT_TRUE(contains_fault_code(result["faults"], "LOCAL_BRAKE_FAULT")) + << "local faults must be present in list_all_faults"; + EXPECT_TRUE(contains_fault_code(result["faults"], "PEER_FAULT")) << "peer faults must be merged into list_all_faults"; + + // "count" must reflect the merged (local + peer) array, not the local-only query. + if (result.contains("count")) { + EXPECT_EQ(result["count"].get(), result["faults"].size()) + << "count must be recomputed after peer faults are merged in"; + } +} + +// @verifies REQ_INTEROP_013 +TEST_F(PluginContextNoAggTest, ListEntityFaults_FunctionResolvesToHostAppFaults) { + ros2_medkit_gateway::FaultManager fm(std::make_shared(make_local_faults())); + auto ctx = ros2_medkit_gateway::make_gateway_plugin_context(node_.get(), &fm, nullptr); + ASSERT_NE(ctx, nullptr); + + // Function "braking" hosts app "brakes" (/vehicle/brakes); its fault must + // surface, and the unrelated /other/sensor fault must not. + auto faults = ctx->list_entity_faults("braking"); + ASSERT_TRUE(faults.is_array()); + EXPECT_TRUE(contains_fault_code(faults, "LOCAL_BRAKE_FAULT")) + << "function must aggregate faults from its host app 'brakes'"; + EXPECT_FALSE(contains_fault_code(faults, "OTHER_NODE_FAULT")) + << "out-of-scope fault must not leak into function 'braking'"; +} + +// @verifies REQ_INTEROP_013 +TEST_F(PluginContextFailingPeerTest, ListEntityFaults_FailingPeerPreservesLocalFaults) { + ros2_medkit_gateway::FaultManager fm(std::make_shared(make_local_faults())); + auto ctx = ros2_medkit_gateway::make_gateway_plugin_context(node_.get(), &fm, nullptr); + ASSERT_NE(ctx, nullptr); + + // The peer 503s on the fault query (partial fan-out), so it contributes + // nothing - but the local fault must still be returned, not silently lost. + auto faults = ctx->list_entity_faults("brakes"); + ASSERT_TRUE(faults.is_array()); + EXPECT_TRUE(contains_fault_code(faults, "LOCAL_BRAKE_FAULT")) + << "local faults must survive when a peer fails the fan-out"; +} + +// @verifies REQ_INTEROP_013 +TEST_F(PluginContextFailingPeerTest, ListAllFaults_FailingPeerPreservesLocalFaults) { + ros2_medkit_gateway::FaultManager fm(std::make_shared(make_local_faults())); + auto ctx = ros2_medkit_gateway::make_gateway_plugin_context(node_.get(), &fm, nullptr); + ASSERT_NE(ctx, nullptr); + + auto result = ctx->list_all_faults(); + ASSERT_TRUE(result.is_object()); + ASSERT_TRUE(result.contains("faults")); + EXPECT_TRUE(contains_fault_code(result["faults"], "LOCAL_BRAKE_FAULT")) + << "local faults must survive when a peer fails the fan-out"; +} diff --git a/src/ros2_medkit_plugins/ros2_medkit_sovd_service_interface/src/sovd_service_interface.cpp b/src/ros2_medkit_plugins/ros2_medkit_sovd_service_interface/src/sovd_service_interface.cpp index 9cb2ad3d3..e42704158 100644 --- a/src/ros2_medkit_plugins/ros2_medkit_sovd_service_interface/src/sovd_service_interface.cpp +++ b/src/ros2_medkit_plugins/ros2_medkit_sovd_service_interface/src/sovd_service_interface.cpp @@ -194,7 +194,12 @@ void SovdServiceInterface::handle_list_entity_faults( fault.fault_code = fault_json.value("fault_code", std::string{}); fault.severity = fault_json.value("severity", static_cast(0)); fault.description = fault_json.value("description", std::string{}); - fault.status = fault_json.value("status", std::string{}); + if (fault_json.contains("status") && fault_json["status"].is_string()) { + fault.status = fault_json["status"].get(); + } else if (fault_json.contains("status") && fault_json["status"].is_object()) { + // Aggregated faults may carry status as a SOVD DTC object; use aggregatedStatus if present + fault.status = fault_json["status"].value("aggregatedStatus", std::string{}); + } fault.occurrence_count = fault_json.value("occurrence_count", static_cast(0)); if (fault_json.contains("first_occurred") && fault_json["first_occurred"].is_number()) { double ts = fault_json["first_occurred"].get();