Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
16 commits
Select commit Hold shift + click to select a range
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
134 changes: 130 additions & 4 deletions docs/tutorials/plugin-system.rst
Original file line number Diff line number Diff line change
Expand Up @@ -241,6 +241,9 @@ providing access to gateway data and utilities:
- ``validate_entity_for_route(req, res, entity_id)`` - validate entity exists and matches the route type, auto-sending SOVD errors on failure
- ``send_error()`` / ``send_json()`` - SOVD-compliant HTTP response helpers (static methods)
- ``register_capability()`` / ``register_entity_capability()`` - register custom capabilities on entities
- ``get_entity_snapshot()`` - returns an ``IntrospectionInput`` populated from the current entity cache
- ``list_all_faults()`` - returns JSON object with a ``"faults"`` array containing all active faults across all entities
- ``register_sampler(collection, fn)`` - registers a cyclic subscription sampler for a custom collection name

.. code-block:: cpp

Expand All @@ -252,15 +255,46 @@ providing access to gateway data and utilities:

// Register a capability for a specific entity
ctx.register_entity_capability("sensor1", "x-medkit-calibration");

// Get a snapshot of all currently discovered entities
IntrospectionInput snapshot = ctx.get_entity_snapshot();

// Query all active faults (returns {"faults": [...]})
nlohmann::json all_faults = ctx.list_all_faults();

// Register a sampler so clients can subscribe to "x-medkit-metrics" cyclically
ctx.register_sampler("x-medkit-metrics",
[this](const std::string& entity_id, const std::string& /*resource_path*/)
-> tl::expected<nlohmann::json, std::string> {
auto data = collect_metrics(entity_id);
if (!data) return tl::make_unexpected("no data for: " + entity_id);
return *data;
});
}

PluginContext* ctx_ = nullptr;

``get_entity_snapshot()`` returns an ``IntrospectionInput`` with vectors for all discovered
areas, components, apps, and functions at the moment of the call. The snapshot is read-only
and reflects the state of the gateway's thread-safe entity cache.

``list_all_faults()`` is useful for plugins that need cross-entity fault visibility (e.g.
mapping fault codes to topics). Returns ``{}`` if the fault manager is unavailable.

``register_sampler(collection, fn)`` wires a sampler into the ``ResourceSamplerRegistry``
so that cyclic subscriptions created for ``collection`` (e.g. ``"x-medkit-metrics"``)
call ``fn(entity_id, resource_path)`` on each tick. The function must return
``tl::expected<nlohmann::json, std::string>``. See `Cyclic Subscription Extensions`_
for the lower-level registry API.

.. note::

The ``PluginContext`` interface is versioned alongside ``PLUGIN_API_VERSION``.
Additional methods (entity data access, configuration queries, etc.) may be added
in future versions.
Breaking changes to existing methods or removal of methods increment the version.
New non-breaking methods (like ``get_entity_snapshot``, ``list_all_faults``, and
``register_sampler``) provide default no-op implementations so plugins that do not
use these methods need no code changes. However, a rebuild is still required because
``plugin_api_version()`` must return the current version (exact-match check).

Custom REST Endpoints
---------------------
Expand Down Expand Up @@ -420,6 +454,98 @@ Multiple plugins can be loaded simultaneously:
All LogProvider plugins receive ``on_log_entry()`` calls as observers.
- **Custom routes**: All plugins can register endpoints (use unique path prefixes)

Graph Provider Plugin (ros2_medkit_graph_provider)
---------------------------------------------------

The gateway ships with an optional first-party plugin that exposes a ROS 2 topic graph for
each SOVD ``Function`` entity. It lives in a separate colcon package,
``ros2_medkit_graph_provider``, under ``src/ros2_medkit_plugins/``.

**What it does**

- Registers the ``x-medkit-graph`` vendor capability on all ``Function`` entities.
- Exposes ``GET /api/v1/functions/{id}/x-medkit-graph`` returning a graph document
with nodes (apps), edges (topic connections), per-edge frequency/latency/drop-rate
metrics (sourced from the ``/diagnostics`` topic), and an overall ``pipeline_status``
(``healthy``, ``degraded``, or ``broken``).
- Supports cyclic subscriptions on the ``x-medkit-graph`` collection so clients can
stream live graph updates.

**Package layout**

.. code-block::

src/ros2_medkit_plugins/
└── ros2_medkit_graph_provider/
├── CMakeLists.txt
├── package.xml
├── include/ros2_medkit_graph_provider/graph_provider_plugin.hpp
└── src/
├── graph_provider_plugin.cpp
└── graph_provider_plugin_exports.cpp

**Loading the plugin**

The plugin is loaded via the ``gateway_params.yaml`` plugin list. The ``.so`` path is
resolved at launch time by ``gateway.launch.py`` using ``get_package_prefix()``; if the
package is not installed the gateway starts normally without graph functionality:

.. code-block:: python

# Excerpt from gateway.launch.py
try:
graph_provider_prefix = get_package_prefix('ros2_medkit_graph_provider')
graph_provider_path = os.path.join(
graph_provider_prefix, 'lib', 'ros2_medkit_graph_provider',
'libros2_medkit_graph_provider_plugin.so')
except PackageNotFoundError:
pass # Plugin not installed - gateway runs without graph provider

The path is then injected into the node parameters as ``plugins.graph_provider.path``.

**YAML configuration**

.. code-block:: yaml

ros2_medkit_gateway:
ros__parameters:
plugins: ["graph_provider"]

# Absolute path to the .so - set automatically by gateway.launch.py
plugins.graph_provider.path: "/opt/ros/jazzy/lib/ros2_medkit_graph_provider/libros2_medkit_graph_provider_plugin.so"

# Default expected publish frequency for topics without per-topic overrides.
# An edge whose measured frequency is below
# expected_frequency_hz_default * degraded_frequency_ratio is marked degraded.
plugins.graph_provider.expected_frequency_hz_default: 30.0

# Fraction of expected frequency below which an edge is "degraded" (0.0-1.0).
plugins.graph_provider.degraded_frequency_ratio: 0.5

# Drop-rate percentage above which an edge is marked degraded.
plugins.graph_provider.drop_rate_percent_threshold: 5.0

Per-function overrides are also supported:

.. code-block:: yaml

# Override thresholds for a specific function
plugins.graph_provider.function_overrides.my_pipeline.expected_frequency_hz: 10.0
plugins.graph_provider.function_overrides.my_pipeline.degraded_frequency_ratio: 0.3
plugins.graph_provider.function_overrides.my_pipeline.drop_rate_percent_threshold: 2.0

**Disabling the plugin**

To disable graph functionality without uninstalling the package, remove ``"graph_provider"``
from the ``plugins`` list in your params file:

.. code-block:: yaml

plugins: []

Alternatively, simply do not install the ``ros2_medkit_graph_provider`` package -
``gateway.launch.py`` will skip the plugin automatically.

Error Handling
--------------

Expand All @@ -434,8 +560,8 @@ Plugins export ``plugin_api_version()`` which must return the gateway's ``PLUGIN
If the version does not match, the plugin is rejected with a clear error message suggesting
a rebuild against matching gateway headers.

The current API version is **1**. It will be incremented when breaking changes are made to
``GatewayPlugin`` or provider interfaces.
The current API version is **4**. It is incremented when the ``PluginContext`` vtable changes
or breaking changes are made to ``GatewayPlugin`` or provider interfaces.

Build Requirements
------------------
Expand Down
9 changes: 0 additions & 9 deletions src/ros2_medkit_gateway/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,6 @@ set(GATEWAY_VERSION "${CMAKE_MATCH_1}")
# Find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(diagnostic_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(std_srvs REQUIRED)
find_package(sensor_msgs REQUIRED)
Expand Down Expand Up @@ -160,7 +159,6 @@ add_library(gateway_lib STATIC
src/plugins/plugin_context.cpp
src/plugins/plugin_loader.cpp
src/plugins/plugin_manager.cpp
src/plugins/graph_provider_plugin.cpp
# OpenAPI documentation module
src/openapi/schema_builder.cpp
src/openapi/path_builder.cpp
Expand All @@ -172,7 +170,6 @@ add_library(gateway_lib STATIC

medkit_target_dependencies(gateway_lib
rclcpp
diagnostic_msgs
std_msgs
std_srvs
rcl_interfaces
Expand Down Expand Up @@ -379,11 +376,6 @@ if(BUILD_TESTING)
ament_add_gtest(test_merge_pipeline test/test_merge_pipeline.cpp)
target_link_libraries(test_merge_pipeline gateway_lib)

# Add graph provider plugin tests
ament_add_gtest(test_graph_provider_plugin test/test_graph_provider_plugin.cpp)
target_link_libraries(test_graph_provider_plugin gateway_lib)
set_tests_properties(test_graph_provider_plugin PROPERTIES ENVIRONMENT "ROS_DOMAIN_ID=70")

# Add capability builder tests
ament_add_gtest(test_capability_builder test/test_capability_builder.cpp)
target_link_libraries(test_capability_builder gateway_lib)
Expand Down Expand Up @@ -614,7 +606,6 @@ if(BUILD_TESTING)
test_log_manager
test_log_handlers
test_merge_pipeline
test_graph_provider_plugin
test_runtime_linker
test_route_descriptions
test_schema_builder
Expand Down
10 changes: 9 additions & 1 deletion src/ros2_medkit_gateway/config/gateway_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -302,7 +302,15 @@ ros2_medkit_gateway:
# Plugin lifecycle: load -> configure -> set_context -> register_routes
# Plugins that throw during any lifecycle call are disabled (not crashed).
# Default: [] (no plugins)
plugins: [""]
plugins: [""] # Default: no plugins. gateway.launch.py adds graph_provider automatically.

# Graph provider plugin - path set by launch file when ros2_medkit_graph_provider is installed
plugins.graph_provider.path: ""

# Graph provider configuration (used when plugin is loaded via launch file)
plugins.graph_provider.expected_frequency_hz_default: 30.0
plugins.graph_provider.degraded_frequency_ratio: 0.5
plugins.graph_provider.drop_rate_percent_threshold: 5.0

# --- Beacon Discovery Plugin (TopicBeaconPlugin) ---
# Subscribes to /ros2_medkit/discovery and enriches discovered entities
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,12 +16,15 @@

#include "ros2_medkit_gateway/lock_manager.hpp"
#include "ros2_medkit_gateway/models/entity_types.hpp"
#include "ros2_medkit_gateway/providers/introspection_provider.hpp"

#include <functional>
#include <httplib.h>
#include <memory>
#include <nlohmann/json.hpp>
#include <optional>
#include <string>
#include <tl/expected.hpp>
#include <unordered_map>
#include <vector>

Expand All @@ -31,6 +34,8 @@ class Node;

namespace ros2_medkit_gateway {

class ResourceSamplerRegistry;

/**
* @brief Entity information exposed to plugins
*/
Expand Down Expand Up @@ -135,6 +140,31 @@ class PluginContext {
/// Get plugin-registered capabilities for a specific entity
virtual std::vector<std::string> get_entity_capabilities(const std::string & entity_id) const = 0;

// ---- Entity bulk access ----

/// Get a snapshot of all discovered entities (areas, components, apps, functions).
/// Returns an IntrospectionInput populated from the current entity cache.
virtual IntrospectionInput get_entity_snapshot() const {
return {};
}

// ---- All-faults access ----

/// List all faults across all entities. Returns JSON with "faults" array.
/// Empty object if fault manager is unavailable.
virtual nlohmann::json list_all_faults() const {
return nlohmann::json::object();
}

// ---- Resource sampler registration ----

/// Register a cyclic subscription sampler for a custom collection.
virtual void register_sampler(
const std::string & /*collection*/,
const std::function<tl::expected<nlohmann::json, std::string>(const std::string &, const std::string &)> &
/*fn*/) {
}

// ---- Locking ----

/**
Expand Down Expand Up @@ -176,6 +206,7 @@ class GatewayNode;
class FaultManager;

/// Factory for creating the concrete gateway plugin context
std::unique_ptr<PluginContext> make_gateway_plugin_context(GatewayNode * node, FaultManager * fault_manager);
std::unique_ptr<PluginContext> make_gateway_plugin_context(GatewayNode * node, FaultManager * fault_manager,
ResourceSamplerRegistry * sampler_registry = nullptr);

} // namespace ros2_medkit_gateway
65 changes: 37 additions & 28 deletions src/ros2_medkit_gateway/launch/gateway.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,59 +14,68 @@

import os

from ament_index_python.packages import get_package_prefix
from ament_index_python.packages import get_package_share_directory
from ament_index_python.packages import PackageNotFoundError
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node


def generate_launch_description():
# Get package directory
pkg_dir = get_package_share_directory('ros2_medkit_gateway')

# Path to default config file
default_config = os.path.join(pkg_dir, 'config', 'gateway_params.yaml')

# Declare launch arguments for easy overriding
# Resolve graph provider plugin path (optional - gateway starts without it)
graph_provider_path = ''
try:
graph_provider_prefix = get_package_prefix('ros2_medkit_graph_provider')
graph_provider_path = os.path.join(
graph_provider_prefix, 'lib', 'ros2_medkit_graph_provider',
'libros2_medkit_graph_provider_plugin.so')
except PackageNotFoundError:
print('[gateway.launch.py] ros2_medkit_graph_provider not installed '
'- graph endpoints will not be available')

if graph_provider_path and not os.path.isfile(graph_provider_path):
print('[gateway.launch.py] WARNING: graph provider .so not found at '
f'{graph_provider_path} - plugin will not load')
graph_provider_path = ''

declare_host_arg = DeclareLaunchArgument(
'server_host',
default_value='127.0.0.1',
description='Host to bind REST server (127.0.0.1 or 0.0.0.0)'
)
'server_host', default_value='127.0.0.1',
description='Host to bind REST server (127.0.0.1 or 0.0.0.0)')

declare_port_arg = DeclareLaunchArgument(
'server_port',
default_value='8080',
description='Port for REST API'
)
'server_port', default_value='8080',
description='Port for REST API')

declare_refresh_arg = DeclareLaunchArgument(
'refresh_interval_ms',
default_value='2000',
description='Cache refresh interval in milliseconds'
)
'refresh_interval_ms', default_value='2000',
description='Cache refresh interval in milliseconds')

# Build parameter overrides - only inject plugin path if found
param_overrides = {
'server.host': LaunchConfiguration('server_host'),
'server.port': LaunchConfiguration('server_port'),
'refresh_interval_ms': LaunchConfiguration('refresh_interval_ms'),
}
if graph_provider_path:
param_overrides['plugins'] = ['graph_provider']
param_overrides['plugins.graph_provider.path'] = graph_provider_path

# Gateway node with parameters
gateway_node = Node(
package='ros2_medkit_gateway',
executable='gateway_node',
name='ros2_medkit_gateway',
output='screen',
parameters=[
default_config, # Load from YAML first
{ # Override with launch arguments
'server.host': LaunchConfiguration('server_host'),
'server.port': LaunchConfiguration('server_port'),
'refresh_interval_ms': LaunchConfiguration('refresh_interval_ms'),
}
],
arguments=['--ros-args', '--log-level', 'info']
)
parameters=[default_config, param_overrides],
arguments=['--ros-args', '--log-level', 'info'])

return LaunchDescription([
declare_host_arg,
declare_port_arg,
declare_refresh_arg,
gateway_node
gateway_node,
])
Loading
Loading