Class TopicDataProvider

Inheritance Relationships

Derived Type

Class Documentation

class TopicDataProvider

Transport-neutral interface for reading and discovering topic data.

This is the infrastructure abstraction consumed by DataAccessManager, DiscoveryManager and RuntimeDiscovery. The ROS 2 default implementation (Ros2TopicDataProvider) services requests via a long-lived subscription pool running under Ros2SubscriptionExecutor. Alternate transports (Zenoh, XRCE-DDS, mocks for tests) plug in by providing another implementation of this interface.

Thread safety

All methods may be called concurrently from multiple HTTP handler threads. Implementations must provide internal synchronization.

Relationship to plugin-facing DataProvider

The unrelated ros2_medkit_gateway::DataProvider in providers/data_provider.hpp is the plugin-authoring interface for per-entity SOVD data resource delegation (list_data / read_data / write_data). It operates at a different architectural layer. Despite the similar name, the two have no inheritance or composition relationship.

Subclassed by ros2_medkit_gateway::Ros2TopicDataProvider

Public Functions

virtual ~TopicDataProvider() = default
TopicDataProvider() = default
TopicDataProvider(const TopicDataProvider&) = delete
TopicDataProvider &operator=(const TopicDataProvider&) = delete
TopicDataProvider(TopicDataProvider&&) = delete
TopicDataProvider &operator=(TopicDataProvider&&) = delete
virtual tl::expected<TopicSampleResult, ErrorInfo> sample(const std::string &topic, std::chrono::milliseconds timeout) = 0

Sample a single topic, returning either fresh data or metadata-only.

If the topic has no publishers, returns metadata-only immediately (has_data == false). Otherwise, waits up to timeout for a message.

virtual tl::expected<std::vector<TopicSampleResult>, ErrorInfo> sample_parallel(const std::vector<std::string> &topics, std::chrono::milliseconds timeout) = 0

Sample multiple topics concurrently, returning one result per input topic.

Order of the returned vector matches the input order. Idle topics return immediately with metadata only; active topics wait up to timeout.

Error semantics (partial-success)

Per-topic recoverable errors (cold-wait cap, subscribe-failed, …) are embedded into the corresponding TopicSampleResult (error_code, error_message, error_http_status) so that one bad topic does not fail an entire bulk read. The top-level tl::unexpected is reserved for batch-fatal conditions only, currently ERR_X_MEDKIT_GATEWAY_SHUTDOWN.

virtual std::optional<TopicInfo> get_topic_info(const std::string &topic) = 0
virtual bool has_publishers(const std::string &topic) = 0
virtual std::vector<TopicInfo> discover(const std::string &namespace_prefix) = 0
virtual std::vector<TopicInfo> discover_all() = 0
virtual std::map<std::string, ComponentTopics> build_component_topic_map() = 0
virtual ComponentTopics get_component_topics(const std::string &component_fqn) = 0
virtual TopicDiscoveryResult discover_topics_by_namespace() = 0
virtual std::set<std::string> discover_topic_namespaces() = 0
virtual ComponentTopics get_topics_for_namespace(const std::string &ns_prefix) = 0
virtual std::vector<TopicEndpoint> get_topic_publishers(const std::string &topic) = 0
virtual std::vector<TopicEndpoint> get_topic_subscribers(const std::string &topic) = 0
virtual TopicConnection get_topic_connection(const std::string &topic) = 0
inline virtual nlohmann::json x_medkit_stats() const

Serialize implementation-specific stats for /health exposure.

Default: empty object. Subclasses that carry runtime state (pool, queue, watchdog) populate this with vendor-extension keys prefixed x-medkit-*. Values must be atomic reads only; /health must not block on this call.