diff --git a/docs/config/discovery-options.rst b/docs/config/discovery-options.rst index 388426462..0b3d0d649 100644 --- a/docs/config/discovery-options.rst +++ b/docs/config/discovery-options.rst @@ -52,6 +52,40 @@ When ``create_synthetic_components`` is true: - ``grouping_strategy: "namespace"`` groups nodes by their first namespace segment - ``synthetic_component_name_pattern`` defines the component ID format +.. note:: + + When ``create_synthetic_areas`` is false, the ``{area}`` placeholder in + ``synthetic_component_name_pattern`` still resolves to the namespace + segment used as the component grouping key - it does not require areas + to be enabled. + +Synthetic Areas +^^^^^^^^^^^^^^^ + +.. code-block:: yaml + + discovery: + runtime: + create_synthetic_areas: true + +When ``create_synthetic_areas`` is true (the default): + +- Areas are created from ROS 2 namespace segments (e.g., ``/powertrain`` becomes area ``powertrain``) +- Components and Apps are organized under these Areas + +When ``create_synthetic_areas`` is false: + +- No Areas are created from namespaces +- The entity tree is flat - Components are top-level entities +- This is useful for simple robots (e.g., TurtleBot3) where an area hierarchy adds unnecessary nesting + +.. code-block:: yaml + + # Flat entity tree - no areas + discovery: + runtime: + create_synthetic_areas: false + Topic-Only Namespaces ^^^^^^^^^^^^^^^^^^^^^ @@ -91,6 +125,11 @@ The ``min_topics_for_component`` parameter (default: 1) sets the minimum number of topics required before creating a component. This can filter out namespaces with only a few stray topics. +.. note:: + + ``create_area_only`` has no effect when ``create_synthetic_areas: false`` - + use ``ignore`` instead. + Merge Pipeline (Hybrid Mode) ----------------------------- @@ -139,7 +178,7 @@ Field Groups * - ``status`` - is_online, bound_fqn * - ``metadata`` - - source, x-medkit extensions, custom metadata fields + - source, ros_binding, external, x-medkit extensions, custom metadata fields Merge Policies ^^^^^^^^^^^^^^ @@ -274,6 +313,9 @@ Complete YAML configuration for runtime discovery: mode: "runtime_only" runtime: + # Create Areas from namespace segments + create_synthetic_areas: true + # Group Apps into Components by namespace create_synthetic_components: true grouping_strategy: "namespace" diff --git a/docs/config/manifest-schema.rst b/docs/config/manifest-schema.rst index f29e9160b..02a734905 100644 --- a/docs/config/manifest-schema.rst +++ b/docs/config/manifest-schema.rst @@ -112,6 +112,12 @@ Areas Areas represent logical or physical groupings (subsystems, locations, etc.). In runtime-only mode, areas are derived from ROS 2 namespaces. +.. note:: + + The ``areas:`` section is optional. For simple robots without subsystem hierarchy, + you can omit areas entirely and use components as the top-level entities. See + :ref:`manifest-flat-entity-tree` below. + Schema ~~~~~~ @@ -727,6 +733,64 @@ Example See the Scripts section in :doc:`/api/rest` for API endpoints. +.. _manifest-flat-entity-tree: + +Flat Entity Tree +---------------- + +For simple robots where the entire system is a single unit, you can omit the +``areas:`` section and use a flat component tree instead. The top-level component +represents the robot itself, with subcomponents for hardware modules: + +.. code-block:: yaml + + manifest_version: "1.0" + + metadata: + name: "flat-turtlebot" + version: "1.0.0" + description: "TurtleBot3 without area hierarchy" + + # No areas section - components are top-level entities + + components: + - id: turtlebot3 + name: "TurtleBot3 Burger" + type: "mobile-robot" + + - id: raspberry-pi + name: "Raspberry Pi 4" + type: "controller" + parent_component_id: turtlebot3 + + - id: lds-sensor + name: "LDS-02 LiDAR" + type: "sensor" + parent_component_id: turtlebot3 + + apps: + - id: lidar-driver + name: "LiDAR Driver" + is_located_on: lds-sensor + ros_binding: + node_name: ld08_driver + namespace: / + +For manifest-based discovery (``manifest_only`` or ``hybrid``), simply omit the +``areas:`` section as shown above - no additional configuration is needed. +For runtime-only discovery, set ``create_synthetic_areas: false`` in +``gateway_params.yaml`` to prevent automatic area creation from namespaces (see +:doc:`discovery-options`). A complete example is available at +``config/examples/flat_robot_manifest.yaml`` in the gateway package. + +.. note:: + + In hybrid mode, the runtime gap-fill layer may create synthetic areas + from namespaces even when the manifest omits ``areas:``. Set + ``merge_pipeline.gap_fill.allow_heuristic_areas: false`` to prevent + this and maintain a fully flat tree. See :doc:`discovery-options` + for gap-fill configuration details. + Complete Example ---------------- diff --git a/docs/getting_started.rst b/docs/getting_started.rst index 92a46c4a7..7d9b6538d 100644 --- a/docs/getting_started.rst +++ b/docs/getting_started.rst @@ -162,10 +162,10 @@ Step 3: Discover Areas and Components ros2_medkit organizes ROS 2 nodes into a SOVD-aligned entity hierarchy: -- **Areas** — Logical/physical domains (e.g., ``/powertrain``, ``/chassis``) -- **Components** — Hardware or virtual units that group Apps -- **Apps** — Individual ROS 2 nodes -- **Functions** — Cross-cutting capabilities (requires manifest mode) +- **Areas** - Logical/physical domains (e.g., ``/powertrain``, ``/chassis``) +- **Components** - Hardware or virtual units that group Apps +- **Apps** - Individual ROS 2 nodes +- **Functions** - Cross-cutting capabilities (requires manifest mode) .. note:: @@ -178,6 +178,10 @@ ros2_medkit organizes ROS 2 nodes into a SOVD-aligned entity hierarchy: links them to live ROS 2 nodes. - **Manifest-only**: Only manifest-declared entities are exposed. + Areas are optional. Simple robots can use a flat component tree without + areas by setting ``discovery.runtime.create_synthetic_areas: false`` or + by omitting the ``areas:`` section in the manifest. + See :doc:`tutorials/manifest-discovery` for details on manifest mode. In this tutorial, we use runtime-only mode with ``demo_nodes.launch.py``. diff --git a/docs/tutorials/manifest-discovery.rst b/docs/tutorials/manifest-discovery.rst index 382b2cbc4..8da9b5327 100644 --- a/docs/tutorials/manifest-discovery.rst +++ b/docs/tutorials/manifest-discovery.rst @@ -272,6 +272,19 @@ Runtime Linking field-group before linking. See :doc:`/config/discovery-options` for merge pipeline configuration. +.. note:: + + **Trigger entity resolution in hybrid mode** + + In hybrid mode, fault and log triggers are delivered using the manifest entity + ID rather than the raw ROS node FQN. The runtime linker builds a node-to-app + mapping during the linking phase (step 4 above), and the fault manager and log + manager use this mapping to resolve incoming trigger events to the correct + manifest entity. This means fault codes, log subscriptions, and SSE events + reference stable manifest IDs (e.g., ``lidar-driver``) instead of the + ephemeral node FQN (e.g., ``/sensors/velodyne_driver``), even when nodes + restart and re-bind. + ROS Binding Configuration ~~~~~~~~~~~~~~~~~~~~~~~~~ @@ -332,19 +345,25 @@ Example response: Entity Hierarchy ---------------- -The manifest defines a hierarchical structure: +The manifest supports two hierarchy patterns depending on your robot's complexity. + +With Areas (Complex Robots) +~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +For robots with multiple subsystems (e.g., autonomous vehicles, industrial platforms), +use areas to group components by function or location: .. code-block:: text Areas (logical/physical groupings) - └── Components (hardware/virtual units) - └── Apps (software applications) - └── Data (topics) - └── Operations (services/actions) - └── Configurations (parameters) + +-- Components (hardware/virtual units) + +-- Apps (software applications) + +-- Data (topics) + +-- Operations (services/actions) + +-- Configurations (parameters) Functions (cross-cutting capabilities) - └── Apps (hosted by) + +-- Apps (hosted by) **Areas** group related components by function or location: @@ -357,7 +376,7 @@ The manifest defines a hierarchical structure: - id: lidar-processing name: "LiDAR Processing" -**Components** represent hardware or virtual units: +**Components** are assigned to areas: .. code-block:: yaml @@ -370,6 +389,60 @@ The manifest defines a hierarchical structure: - id: gpu-unit name: "GPU Processing Unit" +Without Areas (Simple Robots) +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +For simple robots where the entire system is a single unit (e.g., TurtleBot3, small +mobile platforms), you can omit areas entirely and use a flat component tree. The +robot itself is the top-level component, with subcomponents for hardware modules: + +.. code-block:: text + + Components (top-level) + +-- Subcomponents (hardware modules) + +-- Apps (software applications) + + Functions (cross-cutting capabilities) + +-- Apps (hosted by) + +.. code-block:: yaml + + # No areas section needed + components: + - id: turtlebot3 + name: "TurtleBot3 Burger" + type: "mobile-robot" + + - id: raspberry-pi + name: "Raspberry Pi 4" + type: "controller" + parent_component_id: turtlebot3 + + apps: + - id: nav2-controller + name: "Nav2 Controller" + is_located_on: raspberry-pi + ros_binding: + node_name: controller_server + namespace: / + +For runtime-only mode, set ``discovery.runtime.create_synthetic_areas: false`` +to prevent automatic area creation from namespaces. See +:ref:`manifest-flat-entity-tree` in the manifest schema reference and +``config/examples/flat_robot_manifest.yaml`` for a complete example. + +**When to use each pattern:** + +- **With areas**: Multiple subsystems, deep namespace hierarchy, large teams + working on separate domains (perception, navigation, control) +- **Without areas**: Single robot with a handful of nodes, flat or shallow + namespace structure, quick prototypes + +Common Elements +~~~~~~~~~~~~~~~ + +Both patterns use **Apps** and **Functions** the same way. + **Apps** are software applications (typically ROS 2 nodes): .. code-block:: yaml diff --git a/src/ros2_medkit_gateway/CMakeLists.txt b/src/ros2_medkit_gateway/CMakeLists.txt index 276534e98..264ff5518 100644 --- a/src/ros2_medkit_gateway/CMakeLists.txt +++ b/src/ros2_medkit_gateway/CMakeLists.txt @@ -365,6 +365,7 @@ if(BUILD_TESTING) ament_add_gtest(test_fault_manager test/test_fault_manager.cpp) target_link_libraries(test_fault_manager gateway_lib) medkit_target_dependencies(test_fault_manager rclcpp ros2_medkit_msgs) + set_tests_properties(test_fault_manager PROPERTIES ENVIRONMENT "ROS_DOMAIN_ID=99") # Add discovery models tests ament_add_gtest(test_discovery_models test/test_discovery_models.cpp) @@ -475,7 +476,7 @@ if(BUILD_TESTING) # Add script handler tests ament_add_gtest(test_script_handlers test/test_script_handlers.cpp) target_link_libraries(test_script_handlers gateway_lib) - set_tests_properties(test_script_handlers PROPERTIES ENVIRONMENT "ROS_DOMAIN_ID=69") + set_tests_properties(test_script_handlers PROPERTIES ENVIRONMENT "ROS_DOMAIN_ID=80") # Add data handler tests ament_add_gtest(test_data_handlers test/test_data_handlers.cpp) @@ -488,6 +489,7 @@ if(BUILD_TESTING) # Add health handler tests ament_add_gtest(test_health_handlers test/test_health_handlers.cpp) target_link_libraries(test_health_handlers gateway_lib) + set_tests_properties(test_health_handlers PROPERTIES ENVIRONMENT "ROS_DOMAIN_ID=79") # Add operation handler tests ament_add_gtest(test_operation_handlers test/test_operation_handlers.cpp) diff --git a/src/ros2_medkit_gateway/config/examples/flat_robot_manifest.yaml b/src/ros2_medkit_gateway/config/examples/flat_robot_manifest.yaml new file mode 100644 index 000000000..2bf048474 --- /dev/null +++ b/src/ros2_medkit_gateway/config/examples/flat_robot_manifest.yaml @@ -0,0 +1,123 @@ +# SOVD System Manifest: Flat Robot (No Areas) +# ============================================ +# This manifest demonstrates a flat entity tree without areas. +# Suitable for simple robots where the entire system is a single component +# with subcomponents representing hardware modules. +# +# Entity tree (no areas - components are top-level): +# turtlebot3 (component) +# +-- raspberry-pi (subcomponent) +# | +-- nav2-controller (app) +# | +-- robot-state-publisher (app) +# +-- opencr-board (subcomponent) +# | +-- turtlebot3-node (app) +# +-- lds-sensor (subcomponent) +# +-- lidar-driver (app) +# +# Functions: +# autonomous-navigation -> nav2-controller, lidar-driver +# teleoperation -> turtlebot3-node, robot-state-publisher +# +# Usage (in gateway_params.yaml or as launch parameter overrides): +# discovery: +# mode: "manifest_only" # or "hybrid" for runtime data +# manifest_path: "/path/to/flat_robot_manifest.yaml" + +manifest_version: "1.0" + +metadata: + name: "flat-turtlebot" + version: "1.0.0" + description: "TurtleBot3 without area hierarchy - single component with subcomponents" + +config: + unmanifested_nodes: warn + inherit_runtime_resources: true + +# No areas section - flat entity tree uses components/subcomponents only + +components: + - id: turtlebot3 + name: "TurtleBot3 Burger" + type: "mobile-robot" + description: "TurtleBot3 Burger mobile platform" + tags: + - robot + - mobile + + - id: raspberry-pi + name: "Raspberry Pi 4" + type: "controller" + parent_component_id: turtlebot3 + description: "Main compute board running ROS 2" + + - id: opencr-board + name: "OpenCR Board" + type: "controller" + parent_component_id: turtlebot3 + description: "Motor controller and sensor interface board" + + - id: lds-sensor + name: "LDS-02 LiDAR" + type: "sensor" + parent_component_id: turtlebot3 + description: "360-degree laser distance sensor" + +apps: + - id: lidar-driver + name: "LiDAR Driver" + category: "driver" + is_located_on: lds-sensor + description: "Publishes laser scans from LDS sensor" + ros_binding: + node_name: ld08_driver + namespace: / + + - id: turtlebot3-node + name: "TurtleBot3 Node" + category: "control" + is_located_on: opencr-board + description: "Differential drive controller and odometry publisher" + ros_binding: + node_name: turtlebot3_node + namespace: / + + - id: nav2-controller + name: "Nav2 Controller" + category: "navigation" + is_located_on: raspberry-pi + description: "Local trajectory tracking controller" + depends_on: + - lidar-driver + ros_binding: + node_name: controller_server + namespace: / + + - id: robot-state-publisher + name: "Robot State Publisher" + category: "control" + is_located_on: raspberry-pi + description: "Publishes robot URDF transforms" + ros_binding: + node_name: robot_state_publisher + namespace: / + +# ============================================================================= +# FUNCTIONS - High-level capabilities +# ============================================================================= +functions: + - id: autonomous-navigation + name: "Autonomous Navigation" + category: "mobility" + description: "Autonomous navigation using Nav2 stack" + hosted_by: + - nav2-controller + - lidar-driver + + - id: teleoperation + name: "Teleoperation" + category: "control" + description: "Manual robot control via velocity commands" + hosted_by: + - turtlebot3-node + - robot-state-publisher diff --git a/src/ros2_medkit_gateway/config/gateway_params.yaml b/src/ros2_medkit_gateway/config/gateway_params.yaml index ea6bc4263..c8a1ee98f 100644 --- a/src/ros2_medkit_gateway/config/gateway_params.yaml +++ b/src/ros2_medkit_gateway/config/gateway_params.yaml @@ -163,6 +163,12 @@ ros2_medkit_gateway: # Runtime (heuristic) discovery options # These control how nodes are mapped to SOVD entities in runtime mode runtime: + # Create synthetic Area entities from ROS 2 namespaces + # When true (default), namespaces become Areas + # When false, no Areas are created - flat component tree + # Useful for simple robots without area hierarchy + create_synthetic_areas: true + # Create synthetic Component entities that group Apps # When true, Components are synthetic groupings (by namespace) # When false, each node is a Component @@ -179,6 +185,8 @@ ros2_medkit_gateway: # Naming pattern for synthetic components # Placeholders: {area} # Examples: "{area}", "{area}_group", "component_{area}" + # When create_synthetic_areas is false, {area} still resolves to + # the namespace segment used as the component grouping key. synthetic_component_name_pattern: "{area}" # Policy for namespaces with topics but no ROS 2 nodes diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/discovery_layer.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/discovery_layer.hpp index 5a612e4e7..a8a44b194 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/discovery_layer.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/discovery_layer.hpp @@ -69,6 +69,19 @@ class DiscoveryLayer { return false; } + /// Number of entities filtered by gap-fill in last discover(). Default 0. + virtual size_t filtered_count() const { + return 0; + } + + /// Return unfiltered runtime apps for post-merge linking. + /// Gap-fill may exclude apps from discover() output, but the linker needs + /// all runtime apps to bind manifest apps to live nodes. + /// Only RuntimeLayer (or test doubles) should override this. + virtual std::vector get_linking_apps() const { + return {}; + } + /// Provide the current discovery context (entities from previous layers). /// Called by MergePipeline before discover(). Default no-op. virtual void set_discovery_context(const IntrospectionInput & /*context*/) { diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/discovery_manager.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/discovery_manager.hpp index 993179442..fde0f6913 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/discovery_manager.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/discovery_manager.hpp @@ -57,6 +57,15 @@ struct DiscoveryConfig { * maps ROS 2 graph entities to SOVD entities. */ struct RuntimeOptions { + /** + * @brief Create synthetic Area entities from ROS 2 namespaces + * + * When true (default), namespaces become Areas. + * When false, no Areas are created - flat component tree. + * Useful for simple robots without area hierarchy. + */ + bool create_synthetic_areas{true}; + /** * @brief Create synthetic Component entities that group Apps * diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/hybrid_discovery.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/hybrid_discovery.hpp index 75c6db437..c3521092b 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/hybrid_discovery.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/hybrid_discovery.hpp @@ -75,7 +75,10 @@ class HybridDiscoveryStrategy : public DiscoveryStrategy { std::vector get_orphan_nodes() const; /** - * @brief Add a discovery layer to the pipeline (e.g., plugin layers) + * @brief Add a discovery layer to the pipeline. + * @warning Construction-time only. Must be called before the first refresh() + * (i.e., before EntityCache timer starts). Calling concurrently with refresh() + * is a data race. */ void add_layer(std::unique_ptr layer); diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/layers/runtime_layer.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/layers/runtime_layer.hpp index da276606d..c8c8bcd99 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/layers/runtime_layer.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/layers/runtime_layer.hpp @@ -46,10 +46,17 @@ class RuntimeLayer : public DiscoveryLayer { void set_gap_fill_config(GapFillConfig config); /// Number of entities filtered by gap-fill config in last discover() - size_t last_filtered_count() const { + size_t filtered_count() const override { return last_filtered_count_; } + /// Return unfiltered runtime apps for post-merge linking. + /// Gap-fill may exclude apps from discover() output, but the linker + /// needs all runtime apps to bind manifest apps to live nodes. + std::vector get_linking_apps() const override { + return linking_apps_; + } + /// Direct access to runtime services (for operation/data endpoints, not part of pipeline) std::vector discover_services(); std::vector discover_actions(); @@ -59,6 +66,7 @@ class RuntimeLayer : public DiscoveryLayer { std::unordered_map policies_; GapFillConfig gap_fill_config_; size_t last_filtered_count_{0}; + std::vector linking_apps_; ///< Unfiltered runtime apps for linker }; } // namespace discovery diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/merge_pipeline.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/merge_pipeline.hpp index e193a2989..c806c3f72 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/merge_pipeline.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/merge_pipeline.hpp @@ -65,6 +65,9 @@ class MergePipeline { /** * @brief Get the last merge report (returned by value for thread safety) + * @warning NOT thread-safe on its own. In production, access only through + * HybridDiscoveryStrategy which holds mutex during reads. Direct calls + * from multiple threads are a data race. */ MergeReport get_last_report() const { return last_report_; @@ -79,6 +82,8 @@ class MergePipeline { /** * @brief Get the last linking result (returned by value for thread safety) + * @warning NOT thread-safe on its own. In production, access only through + * HybridDiscoveryStrategy which holds mutex during reads. */ LinkingResult get_linking_result() const { return linking_result_; @@ -96,6 +101,7 @@ class MergePipeline { std::unique_ptr linker_; ManifestConfig manifest_config_; LinkingResult linking_result_; + bool executed_{false}; }; } // namespace discovery diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/runtime_discovery.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/runtime_discovery.hpp index a0c6e6586..099a19ce2 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/runtime_discovery.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/discovery/runtime_discovery.hpp @@ -61,6 +61,7 @@ class RuntimeDiscoveryStrategy : public DiscoveryStrategy { * @brief Runtime discovery configuration options */ struct RuntimeConfig { + bool create_synthetic_areas{true}; bool create_synthetic_components{true}; ComponentGroupingStrategy grouping{}; std::string synthetic_component_name_pattern{"{area}"}; 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 index a0e4ebfcc..8ca7915c2 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/log_manager.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/log_manager.hpp @@ -16,6 +16,7 @@ #include #include +#include #include #include #include @@ -122,6 +123,15 @@ class LogManager { /// Called by GatewayNode after both LogManager and the notifier are available. void set_notifier(ResourceChangeNotifier * notifier); + /// Callback that maps a ROS 2 node FQN to a manifest entity ID. + /// Returns empty string if the FQN cannot be resolved. + using NodeToEntityFn = std::function; + + /// Set the node-to-entity resolver for trigger notifications. + /// When set, on_rosout() resolves node names to manifest entity IDs before + /// notifying the ResourceChangeNotifier. + void set_node_to_entity_resolver(NodeToEntityFn resolver); + // ---- Static utilities (no ROS 2 required — safe in unit tests) ---- /// Convert ROS 2 uint8 log level -> SOVD severity string ("debug" for unknown levels) @@ -158,6 +168,9 @@ class LogManager { rclcpp::Node * node_; PluginManager * plugin_mgr_; ResourceChangeNotifier * notifier_ = nullptr; + /// Write-once: must be set before ROS executor starts spinning. + /// After that, only read from subscription callbacks (no mutex needed). + NodeToEntityFn node_to_entity_resolver_; size_t max_buffer_size_; rclcpp::Subscription::SharedPtr rosout_sub_; diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/models/thread_safe_entity_cache.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/models/thread_safe_entity_cache.hpp index 2aa44e0a9..82e9009a8 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/models/thread_safe_entity_cache.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/models/thread_safe_entity_cache.hpp @@ -166,9 +166,10 @@ class ThreadSafeEntityCache { * @param components All discovered components * @param apps All discovered apps * @param functions All discovered functions + * @param node_to_app Node FQN to app entity ID mapping from linking result (optional) */ void update_all(std::vector areas, std::vector components, std::vector apps, - std::vector functions); + std::vector functions, std::unordered_map node_to_app = {}); /** * @brief Incremental update for single entity type @@ -221,6 +222,21 @@ class ThreadSafeEntityCache { */ std::string get_topic_type(const std::string & topic_name) const; + // --- Node-to-app mapping (for trigger entity resolution) --- + /** + * @brief Get the node FQN to app entity ID mapping + * + * Used by trigger subscribers to resolve ROS 2 node FQNs to manifest + * entity IDs. The mapping is populated from the linking result during + * cache refresh. + * + * @return Map of node FQN -> app entity ID (empty if no linking available) + */ + std::unordered_map get_node_to_app() const; + + /// Look up a single node FQN to app entity ID mapping (shared lock, no map copy) + std::string resolve_node_to_app(const std::string & node_fqn) const; + // --- Resolve any entity by ID --- std::optional find_entity(const std::string & id) const; SovdEntityType get_entity_type(const std::string & id) const; @@ -448,9 +464,12 @@ class ThreadSafeEntityCache { // Operation index (operation full_path → owning entity) std::unordered_map operation_index_; - // Topic type cache (topic name → message type) - refreshed periodically + // Topic type cache (topic name -> message type) - refreshed periodically std::unordered_map topic_type_cache_; + // Node FQN -> app entity ID mapping from linking result (for trigger entity resolution) + std::unordered_map node_to_app_; + // Internal helpers (called under lock) void rebuild_all_indexes(); void rebuild_area_index(); diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/trigger_fault_subscriber.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/trigger_fault_subscriber.hpp index 8754ff040..a7d82f2fa 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/trigger_fault_subscriber.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/trigger_fault_subscriber.hpp @@ -14,7 +14,9 @@ #pragma once +#include #include +#include #include "rclcpp/rclcpp.hpp" #include "ros2_medkit_gateway/resource_change_notifier.hpp" @@ -43,6 +45,13 @@ class TriggerFaultSubscriber { */ TriggerFaultSubscriber(rclcpp::Node * node, ResourceChangeNotifier & notifier); + /// Callback to resolve ROS node FQN to manifest entity ID. + /// Returns manifest entity ID, or empty string if not resolvable. + using NodeToEntityFn = std::function; + + /// Set the node-to-entity resolver for manifest entity ID lookup. + void set_node_to_entity_resolver(NodeToEntityFn resolver); + // Non-copyable, non-movable TriggerFaultSubscriber(const TriggerFaultSubscriber &) = delete; TriggerFaultSubscriber & operator=(const TriggerFaultSubscriber &) = delete; @@ -56,6 +65,9 @@ class TriggerFaultSubscriber { rclcpp::Subscription::SharedPtr subscription_; ResourceChangeNotifier & notifier_; rclcpp::Logger logger_; + /// Write-once: must be set before ROS executor starts spinning. + /// After that, only read from subscription callbacks (no mutex needed). + NodeToEntityFn node_to_entity_resolver_; }; } // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/src/discovery/discovery_manager.cpp b/src/ros2_medkit_gateway/src/discovery/discovery_manager.cpp index 5bf4d4c17..b127accf5 100644 --- a/src/ros2_medkit_gateway/src/discovery/discovery_manager.cpp +++ b/src/ros2_medkit_gateway/src/discovery/discovery_manager.cpp @@ -96,6 +96,7 @@ void DiscoveryManager::apply_layer_policy_overrides(const std::string & layer_na void DiscoveryManager::create_strategy() { // Configure runtime strategy with runtime options discovery::RuntimeDiscoveryStrategy::RuntimeConfig runtime_config; + runtime_config.create_synthetic_areas = config_.runtime.create_synthetic_areas; runtime_config.create_synthetic_components = config_.runtime.create_synthetic_components; runtime_config.grouping = config_.runtime.grouping; runtime_config.synthetic_component_name_pattern = config_.runtime.synthetic_component_name_pattern; diff --git a/src/ros2_medkit_gateway/src/discovery/hybrid_discovery.cpp b/src/ros2_medkit_gateway/src/discovery/hybrid_discovery.cpp index 4a4ee1cc3..9bf0b9ff6 100644 --- a/src/ros2_medkit_gateway/src/discovery/hybrid_discovery.cpp +++ b/src/ros2_medkit_gateway/src/discovery/hybrid_discovery.cpp @@ -46,9 +46,16 @@ std::vector HybridDiscoveryStrategy::discover_functions() { } void HybridDiscoveryStrategy::refresh() { - // Hold mutex for the full execute()+swap to prevent data races with add_layer() + // Execute pipeline WITHOUT lock - safe because: + // 1. add_layer() is construction-only (called in DiscoveryManager::initialize() + // before EntityCache timer starts refresh cycles) + // 2. refresh() is only called from the ROS executor timer callback (single-threaded) + // - concurrent refresh() calls cannot occur under the default executor model + auto new_result = pipeline_.execute(); + + // Swap result under lock to protect concurrent discover_*() readers std::lock_guard lock(mutex_); - cached_result_ = pipeline_.execute(); + cached_result_ = std::move(new_result); if (node_) { RCLCPP_INFO(node_->get_logger(), "Hybrid discovery refreshed: %zu entities", cached_result_.report.total_entities); } @@ -70,7 +77,6 @@ std::vector HybridDiscoveryStrategy::get_orphan_nodes() const { } void HybridDiscoveryStrategy::add_layer(std::unique_ptr layer) { - std::lock_guard lock(mutex_); pipeline_.add_layer(std::move(layer)); } diff --git a/src/ros2_medkit_gateway/src/discovery/layers/runtime_layer.cpp b/src/ros2_medkit_gateway/src/discovery/layers/runtime_layer.cpp index ff36ae554..ea394ab1f 100644 --- a/src/ros2_medkit_gateway/src/discovery/layers/runtime_layer.cpp +++ b/src/ros2_medkit_gateway/src/discovery/layers/runtime_layer.cpp @@ -92,6 +92,7 @@ RuntimeLayer::RuntimeLayer(RuntimeDiscoveryStrategy * runtime_strategy) : runtim LayerOutput RuntimeLayer::discover() { LayerOutput output; last_filtered_count_ = 0; + linking_apps_.clear(); if (!runtime_strategy_) { return output; } @@ -101,8 +102,11 @@ LayerOutput RuntimeLayer::discover() { last_filtered_count_ += filter_by_namespace(output.areas, gap_fill_config_); } - // Discover apps once - used by both components (synthetic grouping) and apps output + // Discover apps once - used by both components (synthetic grouping) and apps output. + // Always save unfiltered apps for post-merge linking. The linker needs all runtime + // apps to bind manifest apps to live nodes, regardless of gap-fill settings. auto apps = runtime_strategy_->discover_apps(); + linking_apps_ = apps; if (gap_fill_config_.allow_heuristic_components) { output.components = runtime_strategy_->discover_components(apps); diff --git a/src/ros2_medkit_gateway/src/discovery/manifest/runtime_linker.cpp b/src/ros2_medkit_gateway/src/discovery/manifest/runtime_linker.cpp index e63b38ef0..accad1a0c 100644 --- a/src/ros2_medkit_gateway/src/discovery/manifest/runtime_linker.cpp +++ b/src/ros2_medkit_gateway/src/discovery/manifest/runtime_linker.cpp @@ -180,6 +180,27 @@ LinkingResult RuntimeLinker::link(const std::vector & manifest_apps, const } } + // Suppress runtime-origin apps that duplicate linked manifest apps (#307). + // After merge_entities(), both manifest apps and runtime synthetic apps may + // appear in the merged input. Remove runtime apps whose bound_fqn matches + // a successfully linked manifest app to avoid duplicates. + std::set linked_fqns; + for (const auto & [app_id, node_fqn] : result.app_to_node) { + linked_fqns.insert(node_fqn); + } + + auto it = std::remove_if(result.linked_apps.begin(), result.linked_apps.end(), [&](const App & app) { + // Only suppress known runtime sources - preserve manifest and plugin entities + if (app.source != "heuristic" && app.source != "topic" && app.source != "synthetic") { + return false; + } + if (!app.bound_fqn.has_value()) { + return false; // Keep apps without bound_fqn + } + return linked_fqns.count(app.bound_fqn.value()) > 0; // Remove if FQN is linked + }); + result.linked_apps.erase(it, result.linked_apps.end()); + // Log summary log_info("Runtime linking: " + result.summary()); diff --git a/src/ros2_medkit_gateway/src/discovery/merge_pipeline.cpp b/src/ros2_medkit_gateway/src/discovery/merge_pipeline.cpp index 674bd3fb7..690690ebe 100644 --- a/src/ros2_medkit_gateway/src/discovery/merge_pipeline.cpp +++ b/src/ros2_medkit_gateway/src/discovery/merge_pipeline.cpp @@ -14,10 +14,12 @@ #include "ros2_medkit_gateway/discovery/merge_pipeline.hpp" -#include "ros2_medkit_gateway/discovery/layers/runtime_layer.hpp" #include "ros2_medkit_gateway/providers/introspection_provider.hpp" +#include #include +#include +#include #include #include #include @@ -93,9 +95,7 @@ void merge_bool(bool & target, bool source, MergeWinner winner) { break; case MergeWinner::BOTH: // OR semantics: once true, stays true. This is intentional for status flags - // like is_online (any layer reporting online = online). For classification - // bools like external, an incorrect true from a lower layer is sticky - - // use AUTHORITATIVE policy on the correcting layer to override. + // like is_online (any layer reporting online = online). target = target || source; break; case MergeWinner::TARGET: @@ -256,11 +256,15 @@ void apply_field_group_merge(Entity & target, const Entity & source, FieldGroup case FieldGroup::STATUS: merge_bool(target.is_online, source.is_online, res.scalar); merge_optional(target.bound_fqn, source.bound_fqn, res.scalar); - merge_bool(target.external, source.external, res.scalar); break; case FieldGroup::METADATA: merge_scalar(target.source, source.source, res.scalar); merge_optional(target.ros_binding, source.ros_binding, res.scalar); + // Use scalar semantics (not OR) - external is a classification, not a status flag + if (res.scalar == MergeWinner::SOURCE) { + target.external = source.external; + } + // TARGET and BOTH: keep target value (no OR semantics) break; } } else if constexpr (std::is_same_v) { @@ -293,6 +297,7 @@ MergePipeline::MergePipeline(rclcpp::Logger logger) : logger_(std::move(logger)) } void MergePipeline::add_layer(std::unique_ptr layer) { + assert(!executed_ && "add_layer() must only be called before first refresh()"); layers_.push_back(std::move(layer)); } @@ -371,6 +376,8 @@ std::vector MergePipeline::merge_entities(std::vectorname()); @@ -414,14 +421,14 @@ MergeResult MergePipeline::execute() { continue; } - // Collect gap-fill filtering stats from RuntimeLayer - auto * runtime_layer = dynamic_cast(layers_[i].get()); - if (runtime_layer) { - report.filtered_by_gap_fill += runtime_layer->last_filtered_count(); - } - // Save runtime apps for the linker BEFORE they are moved into app_layers below. - if (runtime_layer || layers_[i]->provides_runtime_apps()) { - runtime_apps = output.apps; + // Collect gap-fill filtering stats (virtual dispatch, no dynamic_cast) + report.filtered_by_gap_fill += layers_[i]->filtered_count(); + + // Save runtime apps for the linker. Use get_linking_apps() which returns + // the unfiltered set - gap-fill may exclude apps from output.apps, but + // the linker needs all runtime apps to bind manifest apps to live nodes. + if (layers_[i]->provides_runtime_apps()) { + runtime_apps = layers_[i]->get_linking_apps(); } if (!output.areas.empty()) { @@ -478,6 +485,60 @@ MergeResult MergePipeline::execute() { linking_result_ = linker_->get_last_result(); result.linking_result = linking_result_; + + // Suppress runtime-origin components/areas that duplicate manifest entities (#307) + // Build set of namespaces covered by linked manifest apps + std::set linked_namespaces; + for (const auto & [fqn, app_id] : linking_result_.node_to_app) { + std::string clean_fqn = fqn; + // Strip trailing slash if present (defensive - ROS 2 normalizes FQNs) + if (clean_fqn.size() > 1 && clean_fqn.back() == '/') { + clean_fqn.pop_back(); + } + auto last_slash = clean_fqn.rfind('/'); + if (last_slash != std::string::npos && last_slash > 0) { + linked_namespaces.insert(clean_fqn.substr(0, last_slash)); + } + // Skip root namespace "/" - too broad, would suppress all root-namespace entities + } + + // Also track manifest component/area namespaces directly + std::set manifest_comp_ns; + for (const auto & comp : result.components) { + if (comp.source == "manifest" && !comp.namespace_path.empty()) { + manifest_comp_ns.insert(comp.namespace_path); + } + } + std::set manifest_area_ns; + for (const auto & area : result.areas) { + if (area.source == "manifest" && !area.namespace_path.empty()) { + manifest_area_ns.insert(area.namespace_path); + } + } + + // Remove runtime components whose namespace is covered + auto comp_it = std::remove_if(result.components.begin(), result.components.end(), [&](const Component & comp) { + // Only suppress known runtime sources - preserve manifest and plugin entities + if (comp.source != "heuristic" && comp.source != "topic" && comp.source != "synthetic") { + return false; + } + return manifest_comp_ns.count(comp.namespace_path) > 0 || linked_namespaces.count(comp.namespace_path) > 0; + }); + result.components.erase(comp_it, result.components.end()); + + // Remove runtime areas whose namespace is covered + auto area_it = std::remove_if(result.areas.begin(), result.areas.end(), [&](const Area & area) { + // Only suppress known runtime sources - preserve manifest and plugin entities + if (area.source != "heuristic" && area.source != "topic" && area.source != "synthetic") { + return false; + } + return manifest_area_ns.count(area.namespace_path) > 0 || linked_namespaces.count(area.namespace_path) > 0; + }); + result.areas.erase(area_it, result.areas.end()); + + // Recount after suppression + report.total_entities = + result.areas.size() + result.components.size() + result.apps.size() + result.functions.size(); } RCLCPP_INFO(logger_, "MergePipeline: %zu entities from %zu layers, %zu enriched, %zu conflicts", diff --git a/src/ros2_medkit_gateway/src/discovery/runtime_discovery.cpp b/src/ros2_medkit_gateway/src/discovery/runtime_discovery.cpp index c7113f24c..b4e7d7be2 100644 --- a/src/ros2_medkit_gateway/src/discovery/runtime_discovery.cpp +++ b/src/ros2_medkit_gateway/src/discovery/runtime_discovery.cpp @@ -59,12 +59,17 @@ RuntimeDiscoveryStrategy::RuntimeDiscoveryStrategy(rclcpp::Node * node) : node_( void RuntimeDiscoveryStrategy::set_config(const RuntimeConfig & config) { config_ = config; - RCLCPP_DEBUG(node_->get_logger(), "Runtime discovery config: synthetic_components=%s, grouping=%s", - config_.create_synthetic_components ? "true" : "false", - grouping_strategy_to_string(config_.grouping).c_str()); + RCLCPP_DEBUG( + node_->get_logger(), "Runtime discovery config: synthetic_areas=%s, synthetic_components=%s, grouping=%s", + config_.create_synthetic_areas ? "true" : "false", config_.create_synthetic_components ? "true" : "false", + grouping_strategy_to_string(config_.grouping).c_str()); } std::vector RuntimeDiscoveryStrategy::discover_areas() { + if (!config_.create_synthetic_areas) { + return {}; + } + // Extract unique areas from namespaces std::set area_set; diff --git a/src/ros2_medkit_gateway/src/gateway_node.cpp b/src/ros2_medkit_gateway/src/gateway_node.cpp index 235a1414d..7c6712725 100644 --- a/src/ros2_medkit_gateway/src/gateway_node.cpp +++ b/src/ros2_medkit_gateway/src/gateway_node.cpp @@ -206,6 +206,7 @@ GatewayNode::GatewayNode(const rclcpp::NodeOptions & options) : Node("ros2_medki // Runtime (heuristic) discovery options // These control how nodes are mapped to SOVD entities in runtime mode + declare_parameter("discovery.runtime.create_synthetic_areas", true); declare_parameter("discovery.runtime.create_synthetic_components", true); declare_parameter("discovery.runtime.grouping_strategy", "namespace"); declare_parameter("discovery.runtime.synthetic_component_name_pattern", "{area}"); @@ -434,6 +435,7 @@ GatewayNode::GatewayNode(const rclcpp::NodeOptions & options) : Node("ros2_medki discovery_config.runtime_enabled = get_parameter("discovery.runtime.enabled").as_bool(); // Runtime discovery options + discovery_config.runtime.create_synthetic_areas = get_parameter("discovery.runtime.create_synthetic_areas").as_bool(); discovery_config.runtime.create_synthetic_components = get_parameter("discovery.runtime.create_synthetic_components").as_bool(); @@ -807,6 +809,32 @@ GatewayNode::GatewayNode(const rclcpp::NodeOptions & options) : Node("ros2_medki trigger_topic_subscriber_ = std::make_unique(this, *resource_change_notifier_); trigger_mgr_->set_topic_subscriber(trigger_topic_subscriber_.get()); + // Wire node-to-entity resolver for trigger notifications (#305). + // The resolver looks up node FQNs in the ThreadSafeEntityCache's node_to_app + // mapping (populated from linking result). Captures 'this' - the lambda is + // called from ROS subscription callbacks on the same node's executor. + auto node_resolver = [this](const std::string & ros_fqn) -> std::string { + auto result = thread_safe_cache_.resolve_node_to_app(ros_fqn); + if (!result.empty()) { + return result; + } + // Try with normalized FQN (strip leading /) + if (!ros_fqn.empty() && ros_fqn[0] == '/') { + result = thread_safe_cache_.resolve_node_to_app(ros_fqn.substr(1)); + if (!result.empty()) { + return result; + } + } + return ""; + }; + + if (trigger_fault_subscriber_) { + trigger_fault_subscriber_->set_node_to_entity_resolver(node_resolver); + } + if (log_mgr_) { + log_mgr_->set_node_to_entity_resolver(node_resolver); + } + RCLCPP_INFO(get_logger(), "Trigger subsystem: enabled (max=%d, storage=%s)", trigger_config.max_triggers, storage_path.empty() ? ":memory:" : storage_path.c_str()); } else { @@ -1255,8 +1283,16 @@ void GatewayNode::refresh_cache() { const size_t app_count = apps.size(); const size_t function_count = functions.size(); - // Update ThreadSafeEntityCache with copies - thread_safe_cache_.update_all(areas, all_components, apps, functions); + // Populate node_to_app mapping for trigger entity resolution (#305) + std::unordered_map node_to_app; + auto linking = discovery_mgr_->get_linking_result(); + if (linking) { + node_to_app = std::move(linking->node_to_app); + } + + // Update ThreadSafeEntityCache atomically (entities + node_to_app under single lock) + thread_safe_cache_.update_all(std::move(areas), std::move(all_components), std::move(apps), std::move(functions), + std::move(node_to_app)); // Update topic type cache (avoids expensive ROS graph queries on /data requests) if (data_access_mgr_) { @@ -1322,6 +1358,7 @@ void GatewayNode::stop_rest_server() { server_cv_.wait(lock, [this] { return !server_running_.load(); }); + lock.unlock(); // Release before join to avoid deadlock server_thread_->join(); } } diff --git a/src/ros2_medkit_gateway/src/log_manager.cpp b/src/ros2_medkit_gateway/src/log_manager.cpp index a08291a78..08f4ea97f 100644 --- a/src/ros2_medkit_gateway/src/log_manager.cpp +++ b/src/ros2_medkit_gateway/src/log_manager.cpp @@ -168,10 +168,41 @@ void LogManager::on_rosout(const rcl_interfaces::msg::Log::ConstSharedPtr & msg) 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(); + // Cap the number of distinct node buffers to prevent unbounded growth. + // Uses max_buffer_size_ * 10 as the cap (e.g., 200 entries -> 2000 distinct nodes). + if (buffers_.find(entry.name) == buffers_.end() && buffers_.size() >= max_buffer_size_ * 10) { + // Silently drop logs from new nodes beyond the cap + } else { + auto & buf = buffers_[entry.name]; + buf.push_back(entry); + if (buf.size() > max_buffer_size_) { + buf.pop_front(); + } + } + } + + // Notify triggers about the log event (resolve ROS node name to entity ID) + if (notifier_) { + std::string entity_id; + + // Try resolving via node_to_app mapping (manifest/hybrid mode) + if (node_to_entity_resolver_) { + // entry.name has no leading '/' (rcl convention), but the mapping + // may use FQNs with leading '/' - try both forms + entity_id = node_to_entity_resolver_("/" + entry.name); + if (entity_id.empty()) { + entity_id = node_to_entity_resolver_(entry.name); + } + } + + // Fallback: extract last path segment (runtime_only mode) + if (entity_id.empty()) { + auto last_slash = entry.name.rfind('/'); + entity_id = (last_slash != std::string::npos) ? entry.name.substr(last_slash + 1) : entry.name; + } + + if (!entity_id.empty()) { + notifier_->notify("logs", entity_id, "", entry_to_json(entry), ChangeType::CREATED); } } } @@ -182,6 +213,10 @@ void LogManager::on_rosout(const rcl_interfaces::msg::Log::ConstSharedPtr & msg) void LogManager::inject_entry_for_testing(LogEntry entry) { std::lock_guard lock(buffers_mutex_); + // Respect buffer cap (same logic as on_rosout) for consistent test behavior + if (buffers_.find(entry.name) == buffers_.end() && buffers_.size() >= max_buffer_size_ * 10) { + return; // Silently drop logs from new nodes beyond the cap + } auto & buf = buffers_[entry.name]; buf.push_back(std::move(entry)); if (buf.size() > max_buffer_size_) { @@ -247,6 +282,10 @@ void LogManager::set_notifier(ResourceChangeNotifier * notifier) { notifier_ = notifier; } +void LogManager::set_node_to_entity_resolver(NodeToEntityFn resolver) { + node_to_entity_resolver_ = std::move(resolver); +} + // --------------------------------------------------------------------------- // effective_provider // --------------------------------------------------------------------------- diff --git a/src/ros2_medkit_gateway/src/models/thread_safe_entity_cache.cpp b/src/ros2_medkit_gateway/src/models/thread_safe_entity_cache.cpp index 57f2745ec..c744f7b1f 100644 --- a/src/ros2_medkit_gateway/src/models/thread_safe_entity_cache.cpp +++ b/src/ros2_medkit_gateway/src/models/thread_safe_entity_cache.cpp @@ -25,13 +25,15 @@ namespace ros2_medkit_gateway { // ============================================================================ void ThreadSafeEntityCache::update_all(std::vector areas, std::vector components, - std::vector apps, std::vector functions) { + std::vector apps, std::vector functions, + std::unordered_map node_to_app) { std::unique_lock lock(mutex_); areas_ = std::move(areas); components_ = std::move(components); apps_ = std::move(apps); functions_ = std::move(functions); + node_to_app_ = std::move(node_to_app); last_update_ = std::chrono::system_clock::now(); rebuild_all_indexes(); @@ -82,6 +84,17 @@ void ThreadSafeEntityCache::update_topic_types(std::unordered_map ThreadSafeEntityCache::get_node_to_app() const { + std::shared_lock lock(mutex_); + return node_to_app_; +} + +std::string ThreadSafeEntityCache::resolve_node_to_app(const std::string & node_fqn) const { + std::shared_lock lock(mutex_); + auto it = node_to_app_.find(node_fqn); + return (it != node_to_app_.end()) ? it->second : ""; +} + // ============================================================================ // Reader methods - List all // ============================================================================ diff --git a/src/ros2_medkit_gateway/src/trigger_fault_subscriber.cpp b/src/ros2_medkit_gateway/src/trigger_fault_subscriber.cpp index 954121554..203add4a9 100644 --- a/src/ros2_medkit_gateway/src/trigger_fault_subscriber.cpp +++ b/src/ros2_medkit_gateway/src/trigger_fault_subscriber.cpp @@ -31,21 +31,32 @@ TriggerFaultSubscriber::TriggerFaultSubscriber(rclcpp::Node * node, ResourceChan RCLCPP_INFO(logger_, "TriggerFaultSubscriber initialized, subscribed to %s", fault_events_topic.c_str()); } +void TriggerFaultSubscriber::set_node_to_entity_resolver(NodeToEntityFn resolver) { + node_to_entity_resolver_ = std::move(resolver); +} + void TriggerFaultSubscriber::on_fault_event(const ros2_medkit_msgs::msg::FaultEvent::ConstSharedPtr & msg) { // Convert fault to JSON using the same method as SSEFaultHandler nlohmann::json fault_json = FaultManager::fault_to_json(msg->fault); fault_json["event_type"] = msg->event_type; // Derive entity_id from reporting_sources (first source, if available). - // reporting_sources contains FQNs like "/powertrain/engine/temp_sensor", - // but triggers use SOVD entity IDs (just the node name, e.g. "temp_sensor"). - // Extract the last segment after the final '/'. + // In hybrid/manifest mode, the resolver maps ROS FQNs to manifest entity IDs. + // Falls back to last-segment extraction for runtime_only mode or when the + // resolver cannot map the FQN. std::string entity_id; if (!msg->fault.reporting_sources.empty()) { - entity_id = msg->fault.reporting_sources[0]; - auto last_slash = entity_id.rfind('/'); - if (last_slash != std::string::npos) { - entity_id = entity_id.substr(last_slash + 1); + auto raw_fqn = msg->fault.reporting_sources[0]; + + // Try resolving ROS FQN to manifest entity ID + if (node_to_entity_resolver_) { + entity_id = node_to_entity_resolver_(raw_fqn); + } + + // Fallback: extract last path segment (backward compat for runtime_only) + if (entity_id.empty()) { + auto last_slash = raw_fqn.rfind('/'); + entity_id = (last_slash != std::string::npos) ? raw_fqn.substr(last_slash + 1) : raw_fqn; } } diff --git a/src/ros2_medkit_gateway/test/test_fault_manager.cpp b/src/ros2_medkit_gateway/test/test_fault_manager.cpp index 840a68b8f..69015e6fd 100644 --- a/src/ros2_medkit_gateway/test/test_fault_manager.cpp +++ b/src/ros2_medkit_gateway/test/test_fault_manager.cpp @@ -134,8 +134,8 @@ TEST_F(FaultManagerTest, GetSnapshotsServiceNotAvailable) { TEST_F(FaultManagerTest, GetSnapshotsSuccessWithValidJson) { // Create mock service auto service = node_->create_service( - "/fault_manager/get_snapshots", - [](const std::shared_ptr request, std::shared_ptr response) { + "/fault_manager/get_snapshots", [](const std::shared_ptr & request, + const std::shared_ptr & response) { response->success = true; nlohmann::json snapshot_data; snapshot_data["fault_code"] = request->fault_code; @@ -170,8 +170,8 @@ TEST_F(FaultManagerTest, GetSnapshotsUsesConfiguredFaultManagerNamespace) { executor_->add_node(node_); auto service = node_->create_service( - "/robot1/fault_manager/get_snapshots", - [](const std::shared_ptr request, std::shared_ptr response) { + "/robot1/fault_manager/get_snapshots", [](const std::shared_ptr & request, + const std::shared_ptr & response) { response->success = true; nlohmann::json snapshot_data; snapshot_data["fault_code"] = request->fault_code; @@ -198,15 +198,15 @@ TEST_F(FaultManagerTest, InvalidFaultManagerNamespaceFallsBackToRootServicePath) executor_ = std::make_unique(); executor_->add_node(node_); - auto service = node_->create_service( - "/fault_manager/get_snapshots", - [](const std::shared_ptr request, std::shared_ptr response) { - response->success = true; - nlohmann::json snapshot_data; - snapshot_data["fault_code"] = request->fault_code; - snapshot_data["service_path"] = "/fault_manager/get_snapshots"; - response->data = snapshot_data.dump(); - }); + auto service = node_->create_service("/fault_manager/get_snapshots", + [](const std::shared_ptr & request, + const std::shared_ptr & response) { + response->success = true; + nlohmann::json snapshot_data; + snapshot_data["fault_code"] = request->fault_code; + snapshot_data["service_path"] = "/fault_manager/get_snapshots"; + response->data = snapshot_data.dump(); + }); start_spinning(); FaultManager fault_manager(node_.get()); @@ -222,8 +222,8 @@ TEST_F(FaultManagerTest, GetSnapshotsSuccessWithTopicFilter) { // Create mock service that verifies topic filter is passed std::string received_topic; auto service = node_->create_service( - "/fault_manager/get_snapshots", [&received_topic](const std::shared_ptr request, - std::shared_ptr response) { + "/fault_manager/get_snapshots", [&received_topic](const std::shared_ptr & request, + const std::shared_ptr & response) { received_topic = request->topic; response->success = true; response->data = "{}"; @@ -239,12 +239,12 @@ TEST_F(FaultManagerTest, GetSnapshotsSuccessWithTopicFilter) { // @verifies REQ_INTEROP_088 TEST_F(FaultManagerTest, GetSnapshotsErrorResponse) { - auto service = node_->create_service( - "/fault_manager/get_snapshots", - [](const std::shared_ptr /*request*/, std::shared_ptr response) { - response->success = false; - response->error_message = "Fault not found"; - }); + auto service = node_->create_service("/fault_manager/get_snapshots", + [](const std::shared_ptr & /*request*/, + const std::shared_ptr & response) { + response->success = false; + response->error_message = "Fault not found"; + }); start_spinning(); FaultManager fault_manager(node_.get()); @@ -257,12 +257,12 @@ TEST_F(FaultManagerTest, GetSnapshotsErrorResponse) { // @verifies REQ_INTEROP_088 TEST_F(FaultManagerTest, GetSnapshotsInvalidJsonFallback) { - auto service = node_->create_service( - "/fault_manager/get_snapshots", - [](const std::shared_ptr /*request*/, std::shared_ptr response) { - response->success = true; - response->data = "not valid json {{{"; - }); + auto service = node_->create_service("/fault_manager/get_snapshots", + [](const std::shared_ptr & /*request*/, + const std::shared_ptr & response) { + response->success = true; + response->data = "not valid json {{{"; + }); start_spinning(); FaultManager fault_manager(node_.get()); @@ -277,12 +277,12 @@ TEST_F(FaultManagerTest, GetSnapshotsInvalidJsonFallback) { // @verifies REQ_INTEROP_088 TEST_F(FaultManagerTest, GetSnapshotsEmptyResponse) { - auto service = node_->create_service( - "/fault_manager/get_snapshots", - [](const std::shared_ptr /*request*/, std::shared_ptr response) { - response->success = true; - response->data = "{}"; - }); + auto service = node_->create_service("/fault_manager/get_snapshots", + [](const std::shared_ptr & /*request*/, + const std::shared_ptr & response) { + response->success = true; + response->data = "{}"; + }); start_spinning(); FaultManager fault_manager(node_.get()); @@ -314,7 +314,7 @@ TEST_F(FaultManagerTest, GetRosbagServiceNotAvailable) { TEST_F(FaultManagerTest, GetRosbagSuccess) { auto service = node_->create_service( "/fault_manager/get_rosbag", - [](const std::shared_ptr request, std::shared_ptr response) { + [](const std::shared_ptr & request, const std::shared_ptr & response) { response->success = true; response->file_path = "/tmp/test_bag_" + request->fault_code; response->format = "sqlite3"; @@ -347,7 +347,7 @@ TEST_F(FaultManagerTest, GetRosbagUsesConfiguredFaultManagerNamespace) { auto service = node_->create_service( "/robot2/fault_manager/get_rosbag", - [](const std::shared_ptr request, std::shared_ptr response) { + [](const std::shared_ptr & request, const std::shared_ptr & response) { response->success = true; response->file_path = "/tmp/" + request->fault_code; response->format = "mcap"; @@ -428,14 +428,141 @@ TEST_F(FaultManagerTest, TriggerFaultSubscriberForwardsNamespacedFaultEvents) { notifier.unsubscribe(subscription_id); } +TEST_F(FaultManagerTest, TriggerFaultSubscriberResolverCalledAndEntityIdUsed) { + // Resolver is called with the raw FQN and the returned entity_id is used in the notification. + node_ = std::make_shared("test_trigger_resolver_called", + rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true)); + executor_ = std::make_unique(); + executor_->add_node(node_); + + ResourceChangeNotifier notifier; + TriggerFaultSubscriber subscriber(node_.get(), notifier); + + std::string received_fqn; + subscriber.set_node_to_entity_resolver([&received_fqn](const std::string & fqn) -> std::string { + received_fqn = fqn; + return "manifest_entity_id"; + }); + + auto publisher = node_->create_publisher("/fault_manager/events", rclcpp::QoS(10)); + + std::promise change_promise; + auto change_future = change_promise.get_future(); + auto subscription_id = notifier.subscribe({"faults", "manifest_entity_id", "/RESOLVER_FAULT"}, + [&change_promise](const ResourceChange & change) { + change_promise.set_value(change); + }); + + ASSERT_TRUE(wait_for_subscription_count("/fault_manager/events", 1u)); + start_spinning(); + + ros2_medkit_msgs::msg::FaultEvent event; + event.event_type = "fault_confirmed"; + event.fault.fault_code = "RESOLVER_FAULT"; + event.fault.reporting_sources.push_back("/pipeline/some_node"); + event.fault.severity = ros2_medkit_msgs::msg::Fault::SEVERITY_ERROR; + publisher->publish(event); + + auto status = change_future.wait_for(2s); + ASSERT_EQ(status, std::future_status::ready); + + auto change = change_future.get(); + EXPECT_EQ(change.entity_id, "manifest_entity_id"); + EXPECT_EQ(received_fqn, "/pipeline/some_node"); + + notifier.unsubscribe(subscription_id); +} + +TEST_F(FaultManagerTest, TriggerFaultSubscriberResolverEmptyFallsBackToLastSegment) { + // When resolver returns empty string, last-segment extraction is used. + node_ = std::make_shared("test_trigger_resolver_empty_fallback", + rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true)); + executor_ = std::make_unique(); + executor_->add_node(node_); + + ResourceChangeNotifier notifier; + TriggerFaultSubscriber subscriber(node_.get(), notifier); + + // Resolver always returns empty -> fallback to last segment + subscriber.set_node_to_entity_resolver([](const std::string & /*fqn*/) -> std::string { + return ""; + }); + + auto publisher = node_->create_publisher("/fault_manager/events", rclcpp::QoS(10)); + + std::promise change_promise; + auto change_future = change_promise.get_future(); + auto subscription_id = notifier.subscribe({"faults", "fallback_node", "/FALLBACK_FAULT"}, + [&change_promise](const ResourceChange & change) { + change_promise.set_value(change); + }); + + ASSERT_TRUE(wait_for_subscription_count("/fault_manager/events", 1u)); + start_spinning(); + + ros2_medkit_msgs::msg::FaultEvent event; + event.event_type = "fault_confirmed"; + event.fault.fault_code = "FALLBACK_FAULT"; + event.fault.reporting_sources.push_back("/pipeline/fallback_node"); + event.fault.severity = ros2_medkit_msgs::msg::Fault::SEVERITY_ERROR; + publisher->publish(event); + + auto status = change_future.wait_for(2s); + ASSERT_EQ(status, std::future_status::ready); + + auto change = change_future.get(); + EXPECT_EQ(change.entity_id, "fallback_node"); + + notifier.unsubscribe(subscription_id); +} + +TEST_F(FaultManagerTest, TriggerFaultSubscriberNoResolverUsesLastSegment) { + // When no resolver is set, last-segment extraction works as before. + node_ = std::make_shared("test_trigger_no_resolver", + rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true)); + executor_ = std::make_unique(); + executor_->add_node(node_); + + ResourceChangeNotifier notifier; + TriggerFaultSubscriber subscriber(node_.get(), notifier); + // No resolver set + + auto publisher = node_->create_publisher("/fault_manager/events", rclcpp::QoS(10)); + + std::promise change_promise; + auto change_future = change_promise.get_future(); + auto subscription_id = notifier.subscribe({"faults", "camera_proc", "/NO_RESOLVER_FAULT"}, + [&change_promise](const ResourceChange & change) { + change_promise.set_value(change); + }); + + ASSERT_TRUE(wait_for_subscription_count("/fault_manager/events", 1u)); + start_spinning(); + + ros2_medkit_msgs::msg::FaultEvent event; + event.event_type = "fault_confirmed"; + event.fault.fault_code = "NO_RESOLVER_FAULT"; + event.fault.reporting_sources.push_back("/sensors/camera_proc"); + event.fault.severity = ros2_medkit_msgs::msg::Fault::SEVERITY_ERROR; + publisher->publish(event); + + auto status = change_future.wait_for(2s); + ASSERT_EQ(status, std::future_status::ready); + + auto change = change_future.get(); + EXPECT_EQ(change.entity_id, "camera_proc"); + + notifier.unsubscribe(subscription_id); +} + // @verifies REQ_INTEROP_088 TEST_F(FaultManagerTest, GetRosbagNotFound) { - auto service = node_->create_service( - "/fault_manager/get_rosbag", - [](const std::shared_ptr /*request*/, std::shared_ptr response) { - response->success = false; - response->error_message = "No rosbag file available for fault"; - }); + auto service = node_->create_service("/fault_manager/get_rosbag", + [](const std::shared_ptr & /*request*/, + const std::shared_ptr & response) { + response->success = false; + response->error_message = "No rosbag file available for fault"; + }); start_spinning(); FaultManager fault_manager(node_.get()); diff --git a/src/ros2_medkit_gateway/test/test_health_handlers.cpp b/src/ros2_medkit_gateway/test/test_health_handlers.cpp index 712f70dfb..e226b76b7 100644 --- a/src/ros2_medkit_gateway/test/test_health_handlers.cpp +++ b/src/ros2_medkit_gateway/test/test_health_handlers.cpp @@ -14,13 +14,22 @@ #include +#include #include +#include #include +#include #include +#include +#include +#include #include "../src/openapi/route_registry.hpp" +#include "ros2_medkit_gateway/gateway_node.hpp" #include "ros2_medkit_gateway/http/handlers/health_handlers.hpp" +using namespace std::chrono_literals; + using json = nlohmann::json; using ros2_medkit_gateway::AuthConfig; using ros2_medkit_gateway::CorsConfig; @@ -38,7 +47,7 @@ using ros2_medkit_gateway::openapi::RouteRegistry; namespace { // No-op handler for route registration in tests -void noop_handler(const httplib::Request &, httplib::Response &) { +void noop_handler(const httplib::Request & /*req*/, httplib::Response & /*res*/) { } // Populate a test route registry with representative routes @@ -265,3 +274,107 @@ TEST_F(HealthHandlersTest, HandleRootTlsEnabledIncludesTlsMetadataBlock) { EXPECT_EQ(body["tls"]["min_version"], "1.3"); EXPECT_TRUE(body["capabilities"]["tls"].get()); } + +// --- handle_health discovery block (requires live GatewayNode) --- + +static constexpr const char * API_BASE_PATH = "/api/v1"; + +static int reserve_free_port() { + int sock = socket(AF_INET, SOCK_STREAM, 0); + if (sock < 0) { + return 0; + } + int opt = 1; + setsockopt(sock, SOL_SOCKET, SO_REUSEADDR, &opt, sizeof(opt)); + 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) { + close(sock); + return 0; + } + socklen_t len = sizeof(addr); + if (getsockname(sock, reinterpret_cast(&addr), &len) != 0) { + close(sock); + return 0; + } + int port = ntohs(addr.sin_port); + close(sock); + return port; +} + +class HealthHandlersLiveTest : public ::testing::Test { + protected: + static void SetUpTestSuite() { + rclcpp::init(0, nullptr); + } + + static void TearDownTestSuite() { + rclcpp::shutdown(); + } + + void SetUp() override { + int free_port = reserve_free_port(); + ASSERT_NE(free_port, 0) << "Failed to reserve a free port for test"; + + rclcpp::NodeOptions options; + options.parameter_overrides({rclcpp::Parameter("server.port", free_port)}); + node_ = std::make_shared(options); + + server_port_ = free_port; + + // Wait for the server to be ready + const auto start = std::chrono::steady_clock::now(); + const auto timeout = std::chrono::seconds(5); + httplib::Client client("127.0.0.1", server_port_); + const std::string health_ep = std::string(API_BASE_PATH) + "/health"; + while (std::chrono::steady_clock::now() - start < timeout) { + if (auto res = client.Get(health_ep)) { + if (res->status == 200) { + return; + } + } + std::this_thread::sleep_for(50ms); + } + FAIL() << "HTTP server failed to start within timeout"; + } + + void TearDown() override { + node_.reset(); + } + + std::shared_ptr node_; + int server_port_{0}; +}; + +TEST_F(HealthHandlersLiveTest, HealthDiscoveryBlockContainsExpectedFields) { + httplib::Client client("127.0.0.1", server_port_); + auto res = client.Get(std::string(API_BASE_PATH) + "/health"); + + ASSERT_TRUE(res); + EXPECT_EQ(res->status, 200); + + auto body = json::parse(res->body); + EXPECT_EQ(body["status"], "healthy"); + EXPECT_TRUE(body.contains("timestamp")); + + // With a live GatewayNode, the discovery block must be present + ASSERT_TRUE(body.contains("discovery")); + auto & disc = body["discovery"]; + + // Must contain mode and strategy strings + ASSERT_TRUE(disc.contains("mode")); + EXPECT_TRUE(disc["mode"].is_string()); + EXPECT_FALSE(disc["mode"].get().empty()); + // Default mode is runtime_only + EXPECT_EQ(disc["mode"].get(), "runtime_only"); + + ASSERT_TRUE(disc.contains("strategy")); + EXPECT_TRUE(disc["strategy"].is_string()); + EXPECT_FALSE(disc["strategy"].get().empty()); + + // In runtime_only mode, pipeline and linking are not present (only in hybrid mode) + EXPECT_FALSE(disc.contains("pipeline")); + EXPECT_FALSE(disc.contains("linking")); +} diff --git a/src/ros2_medkit_gateway/test/test_log_manager.cpp b/src/ros2_medkit_gateway/test/test_log_manager.cpp index 4871e6469..709d5f8ec 100644 --- a/src/ros2_medkit_gateway/test/test_log_manager.cpp +++ b/src/ros2_medkit_gateway/test/test_log_manager.cpp @@ -14,12 +14,18 @@ #include #include +#include #include +#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" +#include "ros2_medkit_gateway/resource_change_notifier.hpp" using json = nlohmann::json; using ros2_medkit_gateway::LogConfig; @@ -725,3 +731,181 @@ TEST_F(LogManagerIngestionTest, PluginGetConfigThrowReturnsError) { ASSERT_FALSE(result.has_value()); EXPECT_NE(result.error().find("plugin get_config failed"), std::string::npos); } + +// ============================================================ +// Resolver notification tests — verify on_rosout() resolves +// node names to entity IDs and passes them to the notifier +// ============================================================ + +class LogManagerResolverTest : public ::testing::Test { + protected: + void SetUp() override { + rclcpp::init(0, nullptr); + node_ = std::make_shared("test_log_resolver"); + notifier_ = std::make_unique(); + mgr_ = std::make_unique(node_.get(), nullptr, 10); + mgr_->set_notifier(notifier_.get()); + + // Subscribe to notifier to capture entity IDs + notifier_->subscribe(ros2_medkit_gateway::NotifierFilter{"logs", "", ""}, + [this](const ros2_medkit_gateway::ResourceChange & change) { + std::lock_guard lock(captured_mutex_); + captured_entity_ids_.push_back(change.entity_id); + }); + + // Create /rosout publisher for sending test log messages + rosout_pub_ = node_->create_publisher("/rosout", 10); + } + + void TearDown() override { + notifier_->shutdown(); + mgr_.reset(); + notifier_.reset(); + rosout_pub_.reset(); + node_.reset(); + rclcpp::shutdown(); + } + + /// Drain any pending /rosout messages (e.g. from LogManager constructor logs) + void drain_initial_messages() { + auto start = std::chrono::steady_clock::now(); + while (std::chrono::steady_clock::now() - start < std::chrono::milliseconds(200)) { + rclcpp::spin_some(node_); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + // Allow notifier worker to process + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + // Clear whatever was captured during startup + std::lock_guard lock(captured_mutex_); + captured_entity_ids_.clear(); + } + + void publish_and_spin(const std::string & logger_name) { + rcl_interfaces::msg::Log msg; + msg.level = rcl_interfaces::msg::Log::INFO; + msg.name = logger_name; + msg.msg = "test message"; + rosout_pub_->publish(msg); + // Spin to process the subscription callback + auto start = std::chrono::steady_clock::now(); + while (std::chrono::steady_clock::now() - start < std::chrono::seconds(2)) { + rclcpp::spin_some(node_); + { + std::lock_guard lock(captured_mutex_); + if (!captured_entity_ids_.empty()) { + break; + } + } + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + // Allow notifier worker thread to process + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } + + std::vector get_captured() { + std::lock_guard lock(captured_mutex_); + return captured_entity_ids_; + } + + std::shared_ptr node_; + std::unique_ptr notifier_; + std::unique_ptr mgr_; + rclcpp::Publisher::SharedPtr rosout_pub_; + + std::mutex captured_mutex_; + std::vector captured_entity_ids_; +}; + +// @verifies REQ_INTEROP_061 +TEST_F(LogManagerResolverTest, ResolverMatchesWithSlashPrefixReturnsEntityId) { + // Resolver returns "temp_sensor_app" when called with "/powertrain/temp_sensor" + mgr_->set_node_to_entity_resolver([](const std::string & fqn) -> std::string { + if (fqn == "/powertrain/temp_sensor") { + return "temp_sensor_app"; + } + return ""; + }); + + // Drain startup log messages that arrive on /rosout before our test message + drain_initial_messages(); + + // /rosout msg.name has no leading slash per rcl convention + publish_and_spin("powertrain/temp_sensor"); + + auto captured = get_captured(); + ASSERT_FALSE(captured.empty()) << "Notifier should have received at least one event"; + EXPECT_EQ(captured[0], "temp_sensor_app"); +} + +// @verifies REQ_INTEROP_061 +TEST_F(LogManagerResolverTest, ResolverMatchesBareNameReturnsEntityId) { + // Resolver returns "my_app" when called with bare name (no leading slash) + mgr_->set_node_to_entity_resolver([](const std::string & fqn) -> std::string { + if (fqn == "simple_node") { + return "my_app"; + } + return ""; + }); + + drain_initial_messages(); + + publish_and_spin("simple_node"); + + auto captured = get_captured(); + ASSERT_FALSE(captured.empty()) << "Notifier should have received at least one event"; + EXPECT_EQ(captured[0], "my_app"); +} + +// @verifies REQ_INTEROP_061 +TEST_F(LogManagerResolverTest, ResolverReturnsEmptyFallsBackToLastSegment) { + // Resolver always returns empty -> on_rosout falls back to last path segment + mgr_->set_node_to_entity_resolver([](const std::string & /*fqn*/) -> std::string { + return ""; + }); + + drain_initial_messages(); + + publish_and_spin("powertrain/engine/temp_sensor"); + + auto captured = get_captured(); + ASSERT_FALSE(captured.empty()) << "Notifier should have received at least one event"; + // Fallback: last segment of "powertrain/engine/temp_sensor" is "temp_sensor" + EXPECT_EQ(captured[0], "temp_sensor"); +} + +// ============================================================ +// Buffer cap test +// ============================================================ + +// @verifies REQ_INTEROP_061 +TEST_F(LogManagerBufferTest, BufferCapDropsNewNodesWhenFull) { + // LogManager was created with buffer size 3 in the fixture. + // Buffer cap = size * 10 = 30 distinct nodes. + // Create a fresh manager with buffer size 5 so cap = 50. + mgr_.reset(); + mgr_ = std::make_unique(node_.get(), nullptr, /*max_buffer_size=*/5); + + // Fill to the cap: 50 distinct nodes + for (int i = 0; i < 50; ++i) { + mgr_->inject_entry_for_testing(make_entry(i, "node_" + std::to_string(i))); + } + + // Verify existing nodes work + auto result_first = mgr_->get_logs({"/node_0"}, false, "", "", ""); + ASSERT_TRUE(result_first.has_value()); + EXPECT_EQ(result_first->size(), 1u); + + // Add one more node beyond the cap - should be silently dropped + mgr_->inject_entry_for_testing(make_entry(999, "new_node_beyond_cap")); + + // The new node's logs should be silently dropped (buffer cap reached) + auto result_new = mgr_->get_logs({"/new_node_beyond_cap"}, false, "", "", ""); + ASSERT_TRUE(result_new.has_value()); + EXPECT_EQ(result_new->size(), 0u) << "Logs from new nodes beyond cap should be dropped"; + + // Existing buffers still work - can add more entries to existing nodes + mgr_->inject_entry_for_testing(make_entry(1000, "node_49")); + auto result_existing = mgr_->get_logs({"/node_49"}, false, "", "", ""); + ASSERT_TRUE(result_existing.has_value()); + EXPECT_EQ(result_existing->size(), 2u); +} diff --git a/src/ros2_medkit_gateway/test/test_merge_pipeline.cpp b/src/ros2_medkit_gateway/test/test_merge_pipeline.cpp index edeb35aa0..ec5bf1777 100644 --- a/src/ros2_medkit_gateway/test/test_merge_pipeline.cpp +++ b/src/ros2_medkit_gateway/test/test_merge_pipeline.cpp @@ -40,6 +40,9 @@ class TestLayer : public DiscoveryLayer { bool provides_runtime_apps() const override { return name_ == "runtime"; } + std::vector get_linking_apps() const override { + return output_.apps; + } LayerOutput discover() override { return output_; } @@ -306,7 +309,7 @@ TEST_F(MergePipelineTest, AuthoritativeVsAuthoritativeHigherPriorityWins) { auto result = pipeline_.execute(); ASSERT_EQ(result.components.size(), 1u); EXPECT_EQ(result.components[0].name, "Manifest Engine"); // higher priority wins - EXPECT_GE(result.report.conflict_count, 1u); // conflict recorded + EXPECT_EQ(result.report.conflict_count, 1u); // conflict recorded } TEST_F(MergePipelineTest, CollectionFieldsUnionOnEnrichment) { @@ -566,7 +569,7 @@ TEST(RuntimeLayerTest, FilteredCountTracked) { // RuntimeLayer with no strategy returns 0 filtered RuntimeLayer layer(nullptr); auto output = layer.discover(); - EXPECT_EQ(layer.last_filtered_count(), 0u); + EXPECT_EQ(layer.filtered_count(), 0u); } // --- Post-merge linking tests --- @@ -760,7 +763,8 @@ TEST_F(MergePipelineTest, MergeConflictStructPopulated) { std::unordered_map{{FieldGroup::IDENTITY, MergePolicy::AUTHORITATIVE}})); auto result = pipeline_.execute(); - ASSERT_GE(result.report.conflicts.size(), 1u); + ASSERT_EQ(result.report.conflicts.size(), 1u); + EXPECT_EQ(result.report.conflict_count, 1u); // Find the IDENTITY conflict for "engine" bool found = false; @@ -1163,5 +1167,481 @@ TEST_F(MergePipelineTest, PolicyOverrideChangedMergeBehavior) { // With both layers AUTH for LIVE_DATA, manifest (higher priority) wins // This means we get a conflict but manifest topics survive EXPECT_EQ(result.components[0].source, "manifest"); - EXPECT_GE(result.report.conflict_count, 1u); + EXPECT_EQ(result.report.conflict_count, 1u); +} + +// --- external field belongs in METADATA, not STATUS (#260c) --- + +// --- Post-linking suppression of duplicate components/areas (#307) --- + +TEST_F(MergePipelineTest, SuppressLinkedRuntimeComponents) { + // Manifest component "lidar-sim" in /sensors + Component manifest_comp = make_component("lidar-sim", "", "/sensors"); + manifest_comp.source = "manifest"; + + // Runtime synthetic component "lidar_sim" in /sensors (heuristic, different ID) + Component runtime_comp = make_component("lidar_sim", "", "/sensors"); + runtime_comp.source = "heuristic"; + + // Manifest app with ros_binding to link + App manifest_app = make_app("lidar_app", "lidar-sim"); + manifest_app.source = "manifest"; + App::RosBinding binding; + binding.node_name = "lidar_node"; + binding.namespace_pattern = "/sensors"; + binding.topic_namespace = ""; + manifest_app.ros_binding = binding; + + // Runtime app (node) that the linker will match + App runtime_node; + runtime_node.id = "lidar_node"; + runtime_node.name = "lidar_node"; + runtime_node.source = "heuristic"; + runtime_node.is_online = true; + runtime_node.bound_fqn = "/sensors/lidar_node"; + + LayerOutput manifest_out; + manifest_out.components.push_back(manifest_comp); + manifest_out.apps.push_back(manifest_app); + + LayerOutput runtime_out; + runtime_out.components.push_back(runtime_comp); + runtime_out.apps.push_back(runtime_node); + + pipeline_.add_layer(std::make_unique( + "manifest", manifest_out, + std::unordered_map{{FieldGroup::IDENTITY, MergePolicy::AUTHORITATIVE}, + {FieldGroup::STATUS, MergePolicy::FALLBACK}})); + pipeline_.add_layer(std::make_unique( + "runtime", runtime_out, + std::unordered_map{{FieldGroup::STATUS, MergePolicy::AUTHORITATIVE}})); + + ManifestConfig manifest_config; + pipeline_.set_linker(std::make_unique(nullptr), manifest_config); + + auto result = pipeline_.execute(); + // Only the manifest component should remain; runtime duplicate suppressed + ASSERT_EQ(result.components.size(), 1u); + EXPECT_EQ(result.components[0].id, "lidar-sim"); + EXPECT_EQ(result.components[0].source, "manifest"); +} + +TEST_F(MergePipelineTest, SuppressLinkedRuntimeAreas) { + // Manifest area "sensors" in /sensors + Area manifest_area; + manifest_area.id = "sensors"; + manifest_area.name = "Sensors"; + manifest_area.namespace_path = "/sensors"; + manifest_area.source = "manifest"; + + // Runtime heuristic area "sensors" in /sensors (same ID, but source differs) + // In practice, IDs might differ, but same namespace is the key + Area runtime_area; + runtime_area.id = "sensors_rt"; + runtime_area.name = "sensors"; + runtime_area.namespace_path = "/sensors"; + runtime_area.source = "heuristic"; + + // Manifest app with ros_binding to create linking + App manifest_app = make_app("sensor_app", "sensor_comp"); + manifest_app.source = "manifest"; + App::RosBinding binding; + binding.node_name = "sensor_node"; + binding.namespace_pattern = "/sensors"; + binding.topic_namespace = ""; + manifest_app.ros_binding = binding; + + // Runtime app (node) + App runtime_node; + runtime_node.id = "sensor_node"; + runtime_node.name = "sensor_node"; + runtime_node.source = "heuristic"; + runtime_node.is_online = true; + runtime_node.bound_fqn = "/sensors/sensor_node"; + + LayerOutput manifest_out; + manifest_out.areas.push_back(manifest_area); + manifest_out.apps.push_back(manifest_app); + + LayerOutput runtime_out; + runtime_out.areas.push_back(runtime_area); + runtime_out.apps.push_back(runtime_node); + + pipeline_.add_layer(std::make_unique( + "manifest", manifest_out, + std::unordered_map{{FieldGroup::IDENTITY, MergePolicy::AUTHORITATIVE}, + {FieldGroup::STATUS, MergePolicy::FALLBACK}})); + pipeline_.add_layer(std::make_unique( + "runtime", runtime_out, + std::unordered_map{{FieldGroup::STATUS, MergePolicy::AUTHORITATIVE}})); + + ManifestConfig manifest_config; + pipeline_.set_linker(std::make_unique(nullptr), manifest_config); + + auto result = pipeline_.execute(); + // Only the manifest area should remain; runtime duplicate suppressed + ASSERT_EQ(result.areas.size(), 1u); + EXPECT_EQ(result.areas[0].id, "sensors"); + EXPECT_EQ(result.areas[0].source, "manifest"); +} + +TEST_F(MergePipelineTest, RuntimeComponentInUncoveredNamespaceNotSuppressed) { + // Manifest component in /sensors namespace + Component manifest_comp = make_component("lidar-sim", "", "/sensors"); + manifest_comp.source = "manifest"; + + // Runtime component in a DIFFERENT namespace (/actuators) - should survive + Component runtime_comp = make_component("motor_ctrl", "", "/actuators"); + runtime_comp.source = "heuristic"; + + // Manifest app with binding in /sensors only + App manifest_app = make_app("lidar_app", "lidar-sim"); + manifest_app.source = "manifest"; + App::RosBinding binding; + binding.node_name = "lidar_node"; + binding.namespace_pattern = "/sensors"; + binding.topic_namespace = ""; + manifest_app.ros_binding = binding; + + // Runtime app in /sensors (will be linked) + App runtime_node; + runtime_node.id = "lidar_node"; + runtime_node.name = "lidar_node"; + runtime_node.source = "heuristic"; + runtime_node.is_online = true; + runtime_node.bound_fqn = "/sensors/lidar_node"; + + LayerOutput manifest_out; + manifest_out.components.push_back(manifest_comp); + manifest_out.apps.push_back(manifest_app); + + LayerOutput runtime_out; + runtime_out.components.push_back(runtime_comp); + runtime_out.apps.push_back(runtime_node); + + pipeline_.add_layer(std::make_unique( + "manifest", manifest_out, + std::unordered_map{{FieldGroup::IDENTITY, MergePolicy::AUTHORITATIVE}, + {FieldGroup::STATUS, MergePolicy::FALLBACK}})); + pipeline_.add_layer(std::make_unique( + "runtime", runtime_out, + std::unordered_map{{FieldGroup::STATUS, MergePolicy::AUTHORITATIVE}})); + + ManifestConfig manifest_config; + pipeline_.set_linker(std::make_unique(nullptr), manifest_config); + + auto result = pipeline_.execute(); + // Both components should remain: manifest in /sensors and runtime in /actuators + ASSERT_EQ(result.components.size(), 2u); + // Verify the uncovered runtime component survived + bool found_motor = false; + for (const auto & c : result.components) { + if (c.id == "motor_ctrl") { + found_motor = true; + EXPECT_EQ(c.source, "heuristic"); + } + } + EXPECT_TRUE(found_motor) << "Runtime component in uncovered namespace should not be suppressed"; +} + +TEST_F(MergePipelineTest, AppExternalField_ManifestAuthoritativeWinsOverRuntime) { + // Manifest layer: METADATA=AUTHORITATIVE, sets external=false (internal node) + App manifest_app = make_app("lidar_proc", "sensor_comp"); + manifest_app.external = false; + + // Runtime layer: METADATA=ENRICHMENT, claims external=true (heuristic) + App runtime_app = make_app("lidar_proc", "sensor_comp"); + runtime_app.external = true; + + LayerOutput manifest_out, runtime_out; + manifest_out.apps.push_back(manifest_app); + runtime_out.apps.push_back(runtime_app); + + pipeline_.add_layer(std::make_unique( + "manifest", manifest_out, + std::unordered_map{{FieldGroup::METADATA, MergePolicy::AUTHORITATIVE}})); + pipeline_.add_layer(std::make_unique( + "runtime", runtime_out, + std::unordered_map{{FieldGroup::METADATA, MergePolicy::ENRICHMENT}})); + + auto result = pipeline_.execute(); + ASSERT_EQ(result.apps.size(), 1u); + // Manifest AUTHORITATIVE METADATA wins: external must be false + EXPECT_FALSE(result.apps[0].external); +} + +// --- Area field group merge tests --- + +TEST_F(MergePipelineTest, AreaIdentityMerge_ManifestAuthoritativeWinsName) { + // Manifest layer (IDENTITY=AUTH) has area with name="Sensors Area" + // Runtime layer (IDENTITY=ENRICHMENT) has same area ID with name="sensors" + // After merge, name should be "Sensors Area" (manifest wins) + Area manifest_area = make_area("sensors", "Sensors Area"); + manifest_area.source = "manifest"; + + Area runtime_area = make_area("sensors", "sensors"); + runtime_area.source = "heuristic"; + + LayerOutput manifest_out, runtime_out; + manifest_out.areas.push_back(manifest_area); + runtime_out.areas.push_back(runtime_area); + + pipeline_.add_layer(std::make_unique( + "manifest", manifest_out, + std::unordered_map{{FieldGroup::IDENTITY, MergePolicy::AUTHORITATIVE}})); + pipeline_.add_layer(std::make_unique( + "runtime", runtime_out, + std::unordered_map{{FieldGroup::IDENTITY, MergePolicy::ENRICHMENT}})); + + auto result = pipeline_.execute(); + ASSERT_EQ(result.areas.size(), 1u); + EXPECT_EQ(result.areas[0].name, "Sensors Area"); +} + +TEST_F(MergePipelineTest, AreaHierarchyMerge_ManifestParentAreaPreserved) { + // Manifest layer (HIERARCHY=AUTH) has area with parent_area_id="vehicle" + // Runtime layer (HIERARCHY=ENRICHMENT) has same area ID with empty parent_area_id + // After merge, parent_area_id should be "vehicle" (manifest wins) + Area manifest_area = make_area("sensors", "Sensors"); + manifest_area.parent_area_id = "vehicle"; + manifest_area.source = "manifest"; + + Area runtime_area = make_area("sensors", "Sensors"); + // runtime has no parent_area_id set (empty string is default) + runtime_area.source = "heuristic"; + + LayerOutput manifest_out, runtime_out; + manifest_out.areas.push_back(manifest_area); + runtime_out.areas.push_back(runtime_area); + + pipeline_.add_layer(std::make_unique( + "manifest", manifest_out, + std::unordered_map{{FieldGroup::HIERARCHY, MergePolicy::AUTHORITATIVE}})); + pipeline_.add_layer(std::make_unique( + "runtime", runtime_out, + std::unordered_map{{FieldGroup::HIERARCHY, MergePolicy::ENRICHMENT}})); + + auto result = pipeline_.execute(); + ASSERT_EQ(result.areas.size(), 1u); + EXPECT_EQ(result.areas[0].parent_area_id, "vehicle"); +} + +// --- merge_bool ENRICHMENT vs ENRICHMENT --- + +TEST_F(MergePipelineTest, MergeBool_EnrichmentVsEnrichment_OrSemantics) { + // Two layers both with STATUS=ENRICHMENT, providing is_online with conflicting values + // ENRICHMENT vs ENRICHMENT resolves to BOTH -> merge_bool uses OR semantics + // false OR true = true + App app1 = make_app("controller", "nav_comp"); + app1.is_online = false; + + App app2 = make_app("controller", "nav_comp"); + app2.is_online = true; + + LayerOutput out1, out2; + out1.apps.push_back(app1); + out2.apps.push_back(app2); + + pipeline_.add_layer(std::make_unique( + "layer1", out1, std::unordered_map{{FieldGroup::STATUS, MergePolicy::ENRICHMENT}})); + pipeline_.add_layer(std::make_unique( + "layer2", out2, std::unordered_map{{FieldGroup::STATUS, MergePolicy::ENRICHMENT}})); + + auto result = pipeline_.execute(); + ASSERT_EQ(result.apps.size(), 1u); + EXPECT_EQ(result.apps[0].is_online, true); +} + +// --- PluginLayer entity ID validation --- + +TEST(PluginLayerTest, ValidationDropsEmptyId) { + auto provider = std::make_shared(); + + App empty_id_app; + empty_id_app.id = ""; + empty_id_app.name = "ghost"; + + App valid_app; + valid_app.id = "valid_app"; + valid_app.name = "Valid App"; + + provider->result_.new_entities.apps = {empty_id_app, valid_app}; + + PluginLayer layer("test_plugin", provider.get()); + auto output = layer.discover(); + ASSERT_EQ(output.apps.size(), 1u); + EXPECT_EQ(output.apps[0].id, "valid_app"); +} + +TEST(PluginLayerTest, ValidationDropsOversizedId) { + auto provider = std::make_shared(); + + App oversized_app; + oversized_app.id = std::string(257, 'a'); // >256 chars + oversized_app.name = "Too Long"; + + App valid_app; + valid_app.id = "ok_app"; + valid_app.name = "OK"; + + provider->result_.new_entities.apps = {oversized_app, valid_app}; + + PluginLayer layer("test_plugin", provider.get()); + auto output = layer.discover(); + ASSERT_EQ(output.apps.size(), 1u); + EXPECT_EQ(output.apps[0].id, "ok_app"); +} + +TEST(PluginLayerTest, ValidationDropsSpecialCharacterId) { + auto provider = std::make_shared(); + + App slash_app; + slash_app.id = "app/with/slashes"; + slash_app.name = "Slashy"; + + App valid_app; + valid_app.id = "clean-app_1"; + valid_app.name = "Clean"; + + provider->result_.new_entities.apps = {slash_app, valid_app}; + + PluginLayer layer("test_plugin", provider.get()); + auto output = layer.discover(); + ASSERT_EQ(output.apps.size(), 1u); + EXPECT_EQ(output.apps[0].id, "clean-app_1"); +} + +TEST(PluginLayerTest, ValidationKeepsAllValidEntities) { + auto provider = std::make_shared(); + + App app1; + app1.id = "alpha"; + App app2; + app2.id = "beta-2"; + App app3; + app3.id = "gamma_3"; + App bad1; + bad1.id = ""; + App bad2; + bad2.id = "has space"; + App bad3; + bad3.id = std::string(257, 'x'); + + provider->result_.new_entities.apps = {app1, bad1, app2, bad2, app3, bad3}; + + PluginLayer layer("test_plugin", provider.get()); + auto output = layer.discover(); + ASSERT_EQ(output.apps.size(), 3u); + EXPECT_EQ(output.apps[0].id, "alpha"); + EXPECT_EQ(output.apps[1].id, "beta-2"); + EXPECT_EQ(output.apps[2].id, "gamma_3"); +} + +// --- create_synthetic_areas=false produces no areas (#261) --- + +TEST_F(MergePipelineTest, CreateSyntheticAreasFalseProducesNoAreas) { + // Simulate a runtime-only layer that provides apps but no areas, + // as would happen with create_synthetic_areas=false on RuntimeDiscoveryStrategy. + // Verify the pipeline works correctly with empty areas and exposes only apps. + + App runtime_app = make_app("sensor_node", ""); + runtime_app.source = "heuristic"; + + LayerOutput runtime_out; + // No areas in output - mirrors RuntimeDiscoveryStrategy with create_synthetic_areas=false + runtime_out.apps.push_back(runtime_app); + + pipeline_.add_layer(std::make_unique( + "runtime", runtime_out, + std::unordered_map{{FieldGroup::STATUS, MergePolicy::AUTHORITATIVE}})); + + auto result = pipeline_.execute(); + EXPECT_TRUE(result.areas.empty()); + ASSERT_EQ(result.apps.size(), 1u); + EXPECT_EQ(result.apps[0].id, "sensor_node"); +} + +// --- Regression for #260c: external field OR bug --- + +// Regression for #260c: external with ENRICHMENT-vs-ENRICHMENT should NOT use OR. +// Both layers METADATA=ENRICHMENT. First layer sets external=false, second sets external=true. +// In the old bug (OR semantics) result would be true. Now first layer wins (value already set). +TEST_F(MergePipelineTest, AppExternalField_EnrichmentDoesNotStickyTrue) { + App layer1_app = make_app("controller", "nav_comp"); + layer1_app.external = false; + + App layer2_app = make_app("controller", "nav_comp"); + layer2_app.external = true; + + LayerOutput out1, out2; + out1.apps.push_back(layer1_app); + out2.apps.push_back(layer2_app); + + pipeline_.add_layer(std::make_unique( + "layer1", out1, std::unordered_map{{FieldGroup::METADATA, MergePolicy::ENRICHMENT}})); + pipeline_.add_layer(std::make_unique( + "layer2", out2, std::unordered_map{{FieldGroup::METADATA, MergePolicy::ENRICHMENT}})); + + auto result = pipeline_.execute(); + ASSERT_EQ(result.apps.size(), 1u); + // First layer's value must win for ENRICHMENT (first-set-wins, not OR). + EXPECT_FALSE(result.apps[0].external); +} + +TEST_F(MergePipelineTest, SuppressDoesNotAffectRootNamespaceEntities) { + // A manifest app bound to a root-level node (/root_node) should NOT + // suppress runtime components with empty namespace_path. + // This tests the last_slash > 0 guard in merge_pipeline.cpp. + + // Manifest app with ros_binding to a root-level node + App manifest_app = make_app("root_app", "some_comp"); + manifest_app.source = "manifest"; + App::RosBinding binding; + binding.node_name = "root_node"; + binding.namespace_pattern = "/"; + binding.topic_namespace = ""; + manifest_app.ros_binding = binding; + + // Runtime app (node at root namespace) + App runtime_node; + runtime_node.id = "root_node"; + runtime_node.name = "root_node"; + runtime_node.source = "heuristic"; + runtime_node.is_online = true; + runtime_node.bound_fqn = "/root_node"; + + // Runtime component with empty namespace_path (root namespace) + Component runtime_comp = make_component("root_comp", "", ""); + runtime_comp.source = "heuristic"; + runtime_comp.namespace_path = ""; + + LayerOutput manifest_out; + manifest_out.apps.push_back(manifest_app); + + LayerOutput runtime_out; + runtime_out.apps.push_back(runtime_node); + runtime_out.components.push_back(runtime_comp); + + pipeline_.add_layer(std::make_unique( + "manifest", manifest_out, + std::unordered_map{{FieldGroup::IDENTITY, MergePolicy::AUTHORITATIVE}, + {FieldGroup::STATUS, MergePolicy::FALLBACK}})); + pipeline_.add_layer(std::make_unique( + "runtime", runtime_out, + std::unordered_map{{FieldGroup::STATUS, MergePolicy::AUTHORITATIVE}})); + + ManifestConfig manifest_config; + pipeline_.set_linker(std::make_unique(nullptr), manifest_config); + + auto result = pipeline_.execute(); + // The runtime component with empty namespace should NOT be suppressed. + // The last_slash > 0 guard prevents "/" FQNs from adding empty string + // to linked_namespaces, which would incorrectly match all root-namespace entities. + bool found_root_comp = false; + for (const auto & c : result.components) { + if (c.id == "root_comp") { + found_root_comp = true; + } + } + EXPECT_TRUE(found_root_comp) << "Runtime component in root namespace should not be suppressed"; } diff --git a/src/ros2_medkit_gateway/test/test_runtime_linker.cpp b/src/ros2_medkit_gateway/test/test_runtime_linker.cpp index 2e60eae93..2fc04afdc 100644 --- a/src/ros2_medkit_gateway/test/test_runtime_linker.cpp +++ b/src/ros2_medkit_gateway/test/test_runtime_linker.cpp @@ -631,7 +631,7 @@ TEST_F(RuntimeLinkerTest, TwoAppsCompeteForSameNode) { EXPECT_EQ(result.unlinked_app_ids.size(), 1u); // Conflict reported - EXPECT_GE(result.binding_conflicts, 1u); + EXPECT_EQ(result.binding_conflicts, 1u); } TEST_F(RuntimeLinkerTest, LinkingReportSummaryIncludesConflicts) { @@ -657,6 +657,153 @@ TEST_F(RuntimeLinkerTest, WildcardMultiMatchCounted) { EXPECT_EQ(result.wildcard_multi_match, 1u); } +// ============================================================================= +// Duplicate Suppression Tests (#307) +// ============================================================================= + +TEST_F(RuntimeLinkerTest, MergedInput_SuppressesRuntimeDuplicates) { + // Bug #307: merge_entities() produces BOTH manifest and runtime apps for the + // same node with different IDs. The merge pipeline passes the merged set as + // the first arg to link(). After link(), linked_apps must NOT contain the + // runtime-origin duplicates - only manifest-source apps should remain. + + // Manifest app with ros_binding targeting the node + App manifest_app; + manifest_app.id = "lidar-sim"; + manifest_app.name = "LiDAR Simulator"; + manifest_app.source = "manifest"; + manifest_app.ros_binding = App::RosBinding{"lidar_sim", "/sensors", ""}; + + // Runtime app representing the same node (from runtime discovery, different ID) + App runtime_origin_app; + runtime_origin_app.id = "lidar_sim"; + runtime_origin_app.name = "lidar_sim"; + runtime_origin_app.source = "heuristic"; + runtime_origin_app.is_online = true; + runtime_origin_app.bound_fqn = "/sensors/lidar_sim"; + runtime_origin_app.topics.publishes = {"/sensors/lidar_sim/scan"}; + + // A second manifest app with a different binding + App manifest_app2; + manifest_app2.id = "imu-driver"; + manifest_app2.name = "IMU Driver"; + manifest_app2.source = "manifest"; + manifest_app2.ros_binding = App::RosBinding{"imu_node", "/sensors", ""}; + + // Runtime app for the second node + App runtime_origin_app2; + runtime_origin_app2.id = "imu_node"; + runtime_origin_app2.name = "imu_node"; + runtime_origin_app2.source = "heuristic"; + runtime_origin_app2.is_online = true; + runtime_origin_app2.bound_fqn = "/sensors/imu_node"; + + // An orphan runtime app (no manifest counterpart) - should be preserved + App orphan_runtime_app; + orphan_runtime_app.id = "camera_node"; + orphan_runtime_app.name = "camera_node"; + orphan_runtime_app.source = "heuristic"; + orphan_runtime_app.is_online = true; + orphan_runtime_app.bound_fqn = "/sensors/camera_node"; + + // Simulate merge_pipeline: first arg is the merged set (manifest + runtime apps) + // second arg is the raw runtime apps used for binding lookups + std::vector merged_apps = {manifest_app, runtime_origin_app, manifest_app2, runtime_origin_app2, + orphan_runtime_app}; + std::vector runtime_apps = {runtime_origin_app, runtime_origin_app2, orphan_runtime_app}; + + auto result = linker_->link(merged_apps, runtime_apps, config_); + + // Both manifest apps should be linked + EXPECT_EQ(result.app_to_node.size(), 2u); + EXPECT_EQ(result.app_to_node["lidar-sim"], "/sensors/lidar_sim"); + EXPECT_EQ(result.app_to_node["imu-driver"], "/sensors/imu_node"); + + // linked_apps should contain exactly 2 manifest apps + 1 orphan runtime app + // The 2 runtime duplicates (lidar_sim, imu_node) whose bound_fqn matches + // a linked manifest app must be suppressed. + EXPECT_EQ(result.linked_apps.size(), 3u); + + // Verify: manifest apps are present and linked + size_t manifest_count = 0; + size_t orphan_count = 0; + for (const auto & app : result.linked_apps) { + if (app.source == "manifest") { + manifest_count++; + EXPECT_TRUE(app.is_online) << "Manifest app should be online: " << app.id; + } else { + orphan_count++; + // The only non-manifest app should be the orphan (camera_node) + EXPECT_EQ(app.id, "camera_node"); + } + } + EXPECT_EQ(manifest_count, 2u); + EXPECT_EQ(orphan_count, 1u); + + // The orphan runtime app should be detected as orphan node + EXPECT_EQ(result.orphan_nodes.size(), 1u); + EXPECT_EQ(result.orphan_nodes[0], "/sensors/camera_node"); +} + +TEST_F(RuntimeLinkerTest, MergedInput_PreservesOrphanRuntimeApps) { + // When runtime apps don't match any manifest app's binding, they should NOT + // be suppressed (they are genuine orphans, not duplicates). + + App manifest_app; + manifest_app.id = "nav-controller"; + manifest_app.name = "Navigation Controller"; + manifest_app.source = "manifest"; + manifest_app.ros_binding = App::RosBinding{"controller", "/nav", ""}; + + // Runtime app matching the manifest binding (duplicate - should be suppressed) + App rt_matching; + rt_matching.id = "controller"; + rt_matching.name = "controller"; + rt_matching.source = "heuristic"; + rt_matching.is_online = true; + rt_matching.bound_fqn = "/nav/controller"; + + // Runtime app NOT matching any manifest binding (orphan - should be preserved) + App rt_orphan; + rt_orphan.id = "planner"; + rt_orphan.name = "planner"; + rt_orphan.source = "heuristic"; + rt_orphan.is_online = true; + rt_orphan.bound_fqn = "/nav/planner"; + + // Simulate merge_pipeline: first arg is merged set + std::vector merged_apps = {manifest_app, rt_matching, rt_orphan}; + std::vector runtime_apps = {rt_matching, rt_orphan}; + + auto result = linker_->link(merged_apps, runtime_apps, config_); + + // Manifest app linked + EXPECT_EQ(result.app_to_node.size(), 1u); + + // linked_apps: 1 manifest app + 1 orphan runtime app (duplicate suppressed) + EXPECT_EQ(result.linked_apps.size(), 2u); + + // Verify the manifest app is present and linked + bool found_manifest = false; + bool found_orphan = false; + for (const auto & app : result.linked_apps) { + if (app.id == "nav-controller") { + found_manifest = true; + EXPECT_EQ(app.source, "manifest"); + EXPECT_TRUE(app.is_online); + } else if (app.id == "planner") { + found_orphan = true; + EXPECT_EQ(app.source, "heuristic"); + } + } + EXPECT_TRUE(found_manifest) << "Manifest app nav-controller not found in linked_apps"; + EXPECT_TRUE(found_orphan) << "Orphan app planner not found in linked_apps"; + + // Orphan still detected in orphan_nodes + EXPECT_EQ(result.orphan_nodes.size(), 1u); + EXPECT_EQ(result.orphan_nodes[0], "/nav/planner"); +} + int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); diff --git a/src/ros2_medkit_integration_tests/test/features/test_discovery_gap_fill.test.py b/src/ros2_medkit_integration_tests/test/features/test_discovery_gap_fill.test.py index ebaa11e4d..efad06b8f 100644 --- a/src/ros2_medkit_integration_tests/test/features/test_discovery_gap_fill.test.py +++ b/src/ros2_medkit_integration_tests/test/features/test_discovery_gap_fill.test.py @@ -115,6 +115,27 @@ def test_only_manifest_components_present(self): f"Unexpected heuristic component found: {comp_id}", ) + def test_manifest_apps_present_and_linked(self): + """With allow_heuristic_apps=true, manifest apps matching launched nodes are present.""" + # 4 demo nodes launched: temp_sensor, rpm_sensor, pressure_sensor, calibration + # These match manifest apps: engine-temp-sensor, engine-rpm-sensor, + # brake-pressure-sensor, engine-calibration-service + expected_linked = { + 'engine-temp-sensor', 'engine-rpm-sensor', + 'brake-pressure-sensor', 'engine-calibration-service', + } + data = self.poll_endpoint_until( + '/apps', + lambda d: d if len(d.get('items', [])) >= len(expected_linked) else None, + timeout=30.0, + ) + app_ids = {a['id'] for a in data['items']} + for app_id in expected_linked: + self.assertIn( + app_id, app_ids, + f"Expected manifest app {app_id} not found in apps list", + ) + def test_health_shows_gap_fill_filtering(self): """Health endpoint should show filtered_by_gap_fill count.""" health = self.poll_endpoint_until( diff --git a/src/ros2_medkit_integration_tests/test/features/test_flat_entity_tree.test.py b/src/ros2_medkit_integration_tests/test/features/test_flat_entity_tree.test.py new file mode 100644 index 000000000..dbdc58fec --- /dev/null +++ b/src/ros2_medkit_integration_tests/test/features/test_flat_entity_tree.test.py @@ -0,0 +1,193 @@ +#!/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. + +"""Integration tests for flat entity tree (no areas). + +Validates that the gateway works correctly in manifest_only mode with a +manifest that defines no areas. Components are top-level entities with +subcomponent hierarchy, and all entity collections return correct counts. + +Uses flat_robot_manifest.yaml which defines: + - 0 areas + - 4 components (turtlebot3 + 3 subcomponents) + - 4 apps (lidar-driver, turtlebot3-node, nav2-controller, robot-state-publisher) + - 2 functions (autonomous-navigation, teleoperation) +""" + +import os +import unittest + +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +import launch_testing +import launch_testing.actions +import launch_testing.asserts + +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_gateway_node + + +def generate_test_description(): + pkg_share = get_package_share_directory('ros2_medkit_gateway') + manifest_path = os.path.join( + pkg_share, 'config', 'examples', 'flat_robot_manifest.yaml' + ) + + gateway_node = create_gateway_node(extra_params={ + 'discovery.mode': 'manifest_only', + 'discovery.manifest_path': manifest_path, + 'discovery.manifest_strict_validation': False, + }) + + return ( + LaunchDescription([ + gateway_node, + launch_testing.actions.ReadyToTest(), + ]), + {'gateway_node': gateway_node}, + ) + + +# @verifies REQ_INTEROP_003 +class TestFlatEntityTree(GatewayTestCase): + """Test entity listing with a flat manifest (no areas).""" + + def test_areas_empty(self): + """GET /areas returns empty list when no areas are defined. + + @verifies REQ_INTEROP_003 + """ + data = self.poll_endpoint_until( + '/areas', + lambda d: d if 'items' in d else None, + timeout=30.0, + ) + self.assertEqual(len(data['items']), 0) + + def test_components_count(self): + """GET /components returns exactly 4 components. + + Expected: turtlebot3 (root) + raspberry-pi, opencr-board, lds-sensor + (subcomponents). + + @verifies REQ_INTEROP_003 + """ + data = self.poll_endpoint_until( + '/components', + lambda d: d if len(d.get('items', [])) >= 4 else None, + timeout=30.0, + ) + components = data['items'] + self.assertEqual(len(components), 4) + + component_ids = sorted([c['id'] for c in components]) + self.assertEqual( + component_ids, + sorted(['turtlebot3', 'raspberry-pi', 'opencr-board', 'lds-sensor']), + ) + + def test_subcomponents_count(self): + """GET /components/turtlebot3/subcomponents returns exactly 3. + + Expected: raspberry-pi, opencr-board, lds-sensor. + + @verifies REQ_INTEROP_003 + """ + data = self.poll_endpoint_until( + '/components/turtlebot3/subcomponents', + lambda d: d if len(d.get('items', [])) >= 3 else None, + timeout=30.0, + ) + subcomponents = data['items'] + self.assertEqual(len(subcomponents), 3) + + sub_ids = sorted([s['id'] for s in subcomponents]) + self.assertEqual( + sub_ids, + sorted(['raspberry-pi', 'opencr-board', 'lds-sensor']), + ) + + def test_apps_count(self): + """GET /apps returns exactly 4 apps. + + Expected: lidar-driver, turtlebot3-node, nav2-controller, + robot-state-publisher. + + @verifies REQ_INTEROP_003 + """ + data = self.poll_endpoint_until( + '/apps', + lambda d: d if len(d.get('items', [])) >= 4 else None, + timeout=30.0, + ) + apps = data['items'] + self.assertEqual(len(apps), 4) + + app_ids = sorted([a['id'] for a in apps]) + self.assertEqual( + app_ids, + sorted([ + 'lidar-driver', 'turtlebot3-node', + 'nav2-controller', 'robot-state-publisher', + ]), + ) + + def test_functions_count(self): + """GET /functions returns exactly 2 functions. + + Expected: autonomous-navigation, teleoperation. + + @verifies REQ_INTEROP_003 + """ + data = self.poll_endpoint_until( + '/functions', + lambda d: d if len(d.get('items', [])) >= 2 else None, + timeout=30.0, + ) + functions = data['items'] + self.assertEqual(len(functions), 2) + + func_ids = sorted([f['id'] for f in functions]) + self.assertEqual( + func_ids, + sorted(['autonomous-navigation', 'teleoperation']), + ) + + def test_app_accessible_without_areas(self): + """GET /apps/lidar-driver returns 200 even without areas. + + Verifies that apps are accessible in a flat entity tree where no + areas are defined. + + @verifies REQ_INTEROP_003 + """ + data = self.poll_endpoint_until( + '/apps/lidar-driver', + lambda d: d if d.get('id') == 'lidar-driver' else None, + timeout=30.0, + ) + self.assertEqual(data['id'], 'lidar-driver') + self.assertIn('name', data) + + +@launch_testing.post_shutdown_test() +class TestShutdown(unittest.TestCase): + + def test_exit_codes(self, proc_info): + """Check all processes exited cleanly (SIGTERM allowed).""" + launch_testing.asserts.assertExitCodes( + proc_info, allowable_exit_codes=ALLOWED_EXIT_CODES + ) diff --git a/src/ros2_medkit_integration_tests/test/features/test_graph_provider_plugin.test.py b/src/ros2_medkit_integration_tests/test/features/test_graph_provider_plugin.test.py index 85bd94f61..35aaf6d9d 100644 --- a/src/ros2_medkit_integration_tests/test/features/test_graph_provider_plugin.test.py +++ b/src/ros2_medkit_integration_tests/test/features/test_graph_provider_plugin.test.py @@ -75,7 +75,7 @@ class TestGraphProviderPlugin(GatewayTestCase): """ MIN_EXPECTED_APPS = 3 - REQUIRED_APPS = {'temp_sensor', 'rpm_sensor', 'pressure_sensor'} + REQUIRED_APPS = {'engine-temp-sensor', 'engine-rpm-sensor', 'brake-pressure-sensor'} def _get_any_function_id(self): """Get the first discovered function ID.""" diff --git a/src/ros2_medkit_integration_tests/test/features/test_hateoas.test.py b/src/ros2_medkit_integration_tests/test/features/test_hateoas.test.py index b9cbf519a..414219b58 100644 --- a/src/ros2_medkit_integration_tests/test/features/test_hateoas.test.py +++ b/src/ros2_medkit_integration_tests/test/features/test_hateoas.test.py @@ -61,7 +61,7 @@ class TestHateoas(GatewayTestCase): MIN_EXPECTED_APPS = 8 REQUIRED_AREAS = {'powertrain', 'chassis', 'body'} - REQUIRED_APPS = {'temp_sensor'} + REQUIRED_APPS = {'engine-temp-sensor'} # ------------------------------------------------------------------ # List hrefs (test_70-72) @@ -167,11 +167,11 @@ def test_app_detail_has_capability_uris(self): @verifies REQ_INTEROP_003 """ - data = self.get_json('/apps/temp_sensor') + data = self.get_json('/apps/engine-temp-sensor') # Verify required fields self.assertIn('id', data) - self.assertEqual(data['id'], 'temp_sensor') + self.assertEqual(data['id'], 'engine-temp-sensor') self.assertIn('name', data) # Verify SOVD capability URIs at top level @@ -180,7 +180,7 @@ def test_app_detail_has_capability_uris(self): self.assertIn('configurations', data, 'App should have configurations URI') # Verify URIs are correct format - base = '/api/v1/apps/temp_sensor' + base = '/api/v1/apps/engine-temp-sensor' self.assertEqual(data['data'], f'{base}/data') self.assertEqual(data['operations'], f'{base}/operations') self.assertEqual(data['configurations'], f'{base}/configurations') @@ -321,7 +321,7 @@ def test_hosts_list_has_href(self): @verifies REQ_INTEROP_007 """ response = requests.get( - f'{self.BASE_URL}/components/powertrain/hosts', + f'{self.BASE_URL}/components/engine-ecu/hosts', timeout=10 ) self.assertEqual(response.status_code, 200) @@ -329,8 +329,8 @@ def test_hosts_list_has_href(self): data = response.json() self.assertIn('items', data) self.assertIn('_links', data) - self.assertEqual(data['_links']['self'], '/api/v1/components/powertrain/hosts') - self.assertEqual(data['_links']['component'], '/api/v1/components/powertrain') + self.assertEqual(data['_links']['self'], '/api/v1/components/engine-ecu/hosts') + self.assertEqual(data['_links']['component'], '/api/v1/components/engine-ecu') for app in data.get('items', []): self.assertIn('id', app, "Hosted app should have 'id'") @@ -378,7 +378,7 @@ def test_depends_on_apps_has_href(self): @verifies REQ_INTEROP_009 """ response = requests.get( - f'{self.BASE_URL}/apps/temp_sensor/depends-on', + f'{self.BASE_URL}/apps/engine-temp-sensor/depends-on', timeout=10 ) self.assertEqual(response.status_code, 200) @@ -386,8 +386,8 @@ def test_depends_on_apps_has_href(self): data = response.json() self.assertIn('items', data) self.assertIn('_links', data) - self.assertEqual(data['_links']['self'], '/api/v1/apps/temp_sensor/depends-on') - self.assertEqual(data['_links']['app'], '/api/v1/apps/temp_sensor') + self.assertEqual(data['_links']['self'], '/api/v1/apps/engine-temp-sensor/depends-on') + self.assertEqual(data['_links']['app'], '/api/v1/apps/engine-temp-sensor') for dep in data.get('items', []): self.assertIn('id', dep, "Dependency should have 'id'") @@ -420,7 +420,7 @@ def test_is_located_on_apps_has_href(self): """GET /apps/{id}/is-located-on returns 0-or-1 component hrefs.""" # @verifies REQ_INTEROP_105 response = requests.get( - f'{self.BASE_URL}/apps/temp_sensor/is-located-on', + f'{self.BASE_URL}/apps/engine-temp-sensor/is-located-on', timeout=10 ) self.assertEqual(response.status_code, 200) @@ -428,8 +428,8 @@ def test_is_located_on_apps_has_href(self): data = response.json() self.assertIn('items', data) self.assertIn('_links', data) - self.assertEqual(data['_links']['self'], '/api/v1/apps/temp_sensor/is-located-on') - self.assertEqual(data['_links']['app'], '/api/v1/apps/temp_sensor') + self.assertEqual(data['_links']['self'], '/api/v1/apps/engine-temp-sensor/is-located-on') + self.assertEqual(data['_links']['app'], '/api/v1/apps/engine-temp-sensor') self.assertLessEqual(len(data['items']), 1) if data['items']: diff --git a/src/ros2_medkit_integration_tests/test/features/test_hybrid_suppression.test.py b/src/ros2_medkit_integration_tests/test/features/test_hybrid_suppression.test.py new file mode 100644 index 000000000..780819bfd --- /dev/null +++ b/src/ros2_medkit_integration_tests/test/features/test_hybrid_suppression.test.py @@ -0,0 +1,282 @@ +#!/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. + +""" +Integration tests for hybrid discovery duplicate suppression (#307). + +Launches the gateway in hybrid mode with the demo_nodes_manifest.yaml and +all demo nodes that match manifest ros_binding entries. Asserts with exact +counts that entity totals match the manifest - no synthetic "root" areas, +no underscored duplicates of components or apps that were already linked. + +Manifest (demo_nodes_manifest.yaml) defines: + - 10 areas (powertrain, engine, chassis, brakes, body, door, + front-left-door, lights, perception, lidar) + - 9 components (engine-ecu, temp-sensor-hw, rpm-sensor-hw, brake-ecu, + brake-pressure-sensor-hw, brake-actuator-hw, + door-sensor-hw, light-module, lidar-unit) + - 9 apps (engine-temp-sensor, engine-rpm-sensor, + engine-calibration-service, engine-long-calibration, + brake-pressure-sensor, brake-actuator, door-status-sensor, + light-controller, lidar-sensor) + - 5 functions (engine-monitoring, engine-calibration, brake-system, + body-electronics, perception-system) +""" + +import os +import unittest + +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import TimerAction +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 ( + ALL_DEMO_NODES, + create_demo_nodes, + create_gateway_node, +) + +# Expected manifest entity counts and IDs +MANIFEST_AREAS = { + 'powertrain', 'engine', 'chassis', 'brakes', 'body', 'door', + 'front-left-door', 'lights', 'perception', 'lidar', +} +MANIFEST_COMPONENTS = { + 'engine-ecu', 'temp-sensor-hw', 'rpm-sensor-hw', 'brake-ecu', + 'brake-pressure-sensor-hw', 'brake-actuator-hw', 'door-sensor-hw', + 'light-module', 'lidar-unit', +} +MANIFEST_APPS = { + 'engine-temp-sensor', 'engine-rpm-sensor', 'engine-calibration-service', + 'engine-long-calibration', 'brake-pressure-sensor', 'brake-actuator', + 'door-status-sensor', 'light-controller', 'lidar-sensor', +} +MANIFEST_FUNCTIONS = { + 'engine-monitoring', 'engine-calibration', 'brake-system', + 'body-electronics', 'perception-system', +} + + +def generate_test_description(): + pkg_share = get_package_share_directory('ros2_medkit_gateway') + manifest_path = os.path.join( + pkg_share, 'config', 'examples', 'demo_nodes_manifest.yaml' + ) + + # Hybrid mode with gap-fill restrictions: only manifest entities allowed. + # All demo nodes match manifest ros_bindings, so the runtime layer + # should link them to manifest apps (not create duplicates). + # Gap-fill blocks heuristic entities for non-manifest nodes (e.g. the + # gateway node itself, param client) so we can assert exact counts. + gateway_node = create_gateway_node(extra_params={ + 'discovery.mode': 'hybrid', + 'discovery.manifest_path': manifest_path, + 'discovery.manifest_strict_validation': False, + 'discovery.merge_pipeline.gap_fill.allow_heuristic_areas': False, + 'discovery.merge_pipeline.gap_fill.allow_heuristic_components': False, + 'discovery.merge_pipeline.gap_fill.allow_heuristic_apps': False, + }) + + # Launch ALL demo nodes so every manifest app gets a runtime match. + demo_nodes = create_demo_nodes(ALL_DEMO_NODES) + delayed = TimerAction(period=2.0, actions=demo_nodes) + + return ( + LaunchDescription([ + gateway_node, + delayed, + launch_testing.actions.ReadyToTest(), + ]), + {'gateway_node': gateway_node}, + ) + + +# @verifies REQ_INTEROP_003 +class TestHybridSuppression(GatewayTestCase): + """Verify hybrid mode suppresses duplicate entities after linking.""" + + # Wait for all manifest apps to be discovered before running tests. + MIN_EXPECTED_APPS = len(MANIFEST_APPS) + REQUIRED_AREAS = MANIFEST_AREAS + REQUIRED_APPS = MANIFEST_APPS + + def test_exact_area_count(self): + """Area count must match manifest exactly - no synthetic extras.""" + # @verifies REQ_INTEROP_003 + data = self.get_json('/areas') + area_ids = {a['id'] for a in data['items']} + self.assertEqual( + area_ids, MANIFEST_AREAS, + f'Area mismatch. Extra: {area_ids - MANIFEST_AREAS}, ' + f'Missing: {MANIFEST_AREAS - area_ids}', + ) + self.assertEqual( + len(data['items']), len(MANIFEST_AREAS), + f'Expected {len(MANIFEST_AREAS)} areas, got {len(data["items"])}: ' + f'{[a["id"] for a in data["items"]]}', + ) + + def test_exact_component_count(self): + """Component count must match manifest exactly - no underscored duplicates.""" + # @verifies REQ_INTEROP_003 + data = self.poll_endpoint_until( + '/components', + lambda d: d if len(d.get('items', [])) == len(MANIFEST_COMPONENTS) else None, + timeout=30.0, + ) + component_ids = {c['id'] for c in data['items']} + self.assertEqual( + component_ids, MANIFEST_COMPONENTS, + f'Component mismatch. Extra: {component_ids - MANIFEST_COMPONENTS}, ' + f'Missing: {MANIFEST_COMPONENTS - component_ids}', + ) + self.assertEqual( + len(data['items']), len(MANIFEST_COMPONENTS), + f'Expected {len(MANIFEST_COMPONENTS)} components, ' + f'got {len(data["items"])}: ' + f'{[c["id"] for c in data["items"]]}', + ) + + def test_exact_app_count(self): + """App count must match manifest exactly - no underscored duplicates.""" + # @verifies REQ_INTEROP_003 + data = self.get_json('/apps') + app_ids = {a['id'] for a in data['items']} + self.assertEqual( + app_ids, MANIFEST_APPS, + f'App mismatch. Extra: {app_ids - MANIFEST_APPS}, ' + f'Missing: {MANIFEST_APPS - app_ids}', + ) + self.assertEqual( + len(data['items']), len(MANIFEST_APPS), + f'Expected {len(MANIFEST_APPS)} apps, got {len(data["items"])}: ' + f'{[a["id"] for a in data["items"]]}', + ) + + def test_exact_function_count(self): + """Function count must match manifest exactly.""" + # @verifies REQ_INTEROP_003 + data = self.poll_endpoint_until( + '/functions', + lambda d: d if len(d.get('items', [])) == len(MANIFEST_FUNCTIONS) else None, + timeout=30.0, + ) + function_ids = {f['id'] for f in data['items']} + self.assertEqual( + function_ids, MANIFEST_FUNCTIONS, + f'Function mismatch. Extra: {function_ids - MANIFEST_FUNCTIONS}, ' + f'Missing: {MANIFEST_FUNCTIONS - function_ids}', + ) + self.assertEqual( + len(data['items']), len(MANIFEST_FUNCTIONS), + f'Expected {len(MANIFEST_FUNCTIONS)} functions, ' + f'got {len(data["items"])}: ' + f'{[f["id"] for f in data["items"]]}', + ) + + def test_no_underscored_app_duplicates(self): + """No apps should have underscore-style IDs from runtime discovery. + + In hybrid mode, runtime nodes matching manifest ros_bindings + should be linked to the manifest app, not create separate + entities like 'powertrain_engine_temp_sensor'. + """ + # @verifies REQ_INTEROP_003 + data = self.get_json('/apps') + app_ids = [a['id'] for a in data['items']] + underscored = [ + aid for aid in app_ids + if '_' in aid and aid not in MANIFEST_APPS + ] + self.assertEqual( + underscored, [], + f'Found underscored runtime duplicate apps: {underscored}', + ) + + def test_no_underscored_component_duplicates(self): + """No components should have underscore-style IDs from runtime heuristics. + + Synthetic components like 'powertrain_engine' should be suppressed + when manifest already defines components for those namespaces. + """ + # @verifies REQ_INTEROP_003 + data = self.get_json('/components') + component_ids = [c['id'] for c in data['items']] + underscored = [ + cid for cid in component_ids + if '_' in cid and cid not in MANIFEST_COMPONENTS + ] + self.assertEqual( + underscored, [], + f'Found underscored runtime duplicate components: {underscored}', + ) + + def test_no_root_or_synthetic_areas(self): + """No 'root' or underscored synthetic areas should exist.""" + # @verifies REQ_INTEROP_003 + data = self.get_json('/areas') + area_ids = [a['id'] for a in data['items']] + synthetic = [ + aid for aid in area_ids + if aid == 'root' or (aid not in MANIFEST_AREAS) + ] + self.assertEqual( + synthetic, [], + f'Found synthetic/unexpected areas: {synthetic}', + ) + + def test_manifest_apps_are_online(self): + """Linked manifest apps should be online after runtime linking. + + Even with allow_heuristic_apps=false (gap-fill blocking runtime + apps from the entity tree), the linker must still receive the + unfiltered runtime apps so it can bind manifest apps to live nodes. + """ + # @verifies REQ_INTEROP_003 + data = self.poll_endpoint_until( + '/apps', + lambda d: d if all( + a.get('x-medkit', {}).get('is_online', False) + for a in d.get('items', []) + ) and len(d.get('items', [])) == len(MANIFEST_APPS) else None, + timeout=30.0, + ) + for app in data['items']: + x_medkit = app.get('x-medkit', {}) + is_online = x_medkit.get('is_online', False) + self.assertTrue( + is_online, + f"App {app['id']} should be online but is not", + ) + + def test_health_shows_hybrid_mode(self): + """Health endpoint should confirm hybrid discovery mode.""" + # @verifies REQ_INTEROP_003 + health = self.get_json('/health') + discovery = health.get('discovery', {}) + self.assertEqual(discovery.get('mode'), 'hybrid') + + +@launch_testing.post_shutdown_test() +class TestShutdown(unittest.TestCase): + + def test_exit_codes(self, proc_info): + launch_testing.asserts.assertExitCodes( + proc_info, allowable_exit_codes=ALLOWED_EXIT_CODES + )