diff --git a/src/ros2_medkit_gateway/CMakeLists.txt b/src/ros2_medkit_gateway/CMakeLists.txt index ab63bce..c08474e 100644 --- a/src/ros2_medkit_gateway/CMakeLists.txt +++ b/src/ros2_medkit_gateway/CMakeLists.txt @@ -130,13 +130,12 @@ add_library(gateway_lib STATIC # HTTP module (subfolder) src/http/http_server.cpp src/http/rest_server.cpp - # HTTP handlers - discovery - src/http/handlers/discovery/area_handlers.cpp - src/http/handlers/discovery/component_handlers.cpp - src/http/handlers/discovery/app_handlers.cpp - src/http/handlers/discovery/function_handlers.cpp + # HTTP handlers - discovery (unified) + src/http/handlers/discovery_handlers.cpp # HTTP handlers - utilities src/http/handlers/capability_builder.cpp + # HTTP handlers - resource handlers (unified across entity types) + src/http/handlers/data_handlers.cpp # HTTP handlers - other src/http/handlers/handler_context.cpp src/http/handlers/health_handlers.cpp diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/data_handlers.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/data_handlers.hpp new file mode 100644 index 0000000..f92b6e4 --- /dev/null +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/data_handlers.hpp @@ -0,0 +1,102 @@ +// Copyright 2026 bburda +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#pragma once + +#include + +#include "ros2_medkit_gateway/http/handlers/handler_context.hpp" + +namespace ros2_medkit_gateway { +namespace handlers { + +/** + * @brief Unified HTTP handlers for data operations across all SOVD entity types + * + * This class provides entity-agnostic handlers for /data endpoints. + * Works for: /areas/{id}/data, /components/{id}/data, /apps/{id}/data, /functions/{id}/data + * + * Key design decisions: + * - Single handler implementation shared across all entity types + * - Entity type resolved from URL regex match or inferred from entity ID + * - Data aggregated from entity hierarchy (e.g., component includes apps' topics) + */ +class DataHandlers { + public: + explicit DataHandlers(HandlerContext & ctx) : ctx_(ctx) { + } + + /** + * @brief List all data items (topics) for an entity + * + * GET /{entities}/{id}/data + * + * URL matches: + * - matches[1]: entity_id + * + * Returns SOVD ValueMetadata items with x-medkit ROS2-specific extensions. + */ + void handle_list_data(const httplib::Request & req, httplib::Response & res); + + /** + * @brief Get a single data item (topic value) for an entity + * + * GET /{entities}/{id}/data/{topic} + * + * URL matches: + * - matches[1]: entity_id + * - matches[2]: topic_id (may be URL-encoded with slashes) + * + * Returns SOVD ReadValue with current topic data and type_info schema. + */ + void handle_get_data_item(const httplib::Request & req, httplib::Response & res); + + /** + * @brief Write data to a topic (publish) + * + * PUT /{entities}/{id}/data/{topic} + * + * URL matches: + * - matches[1]: entity_id + * - matches[2]: topic_id (may be URL-encoded with slashes) + * + * Request body: { "type": "pkg/msg/Type", "data": {...} } + * Returns SOVD WriteValue with echoed data. + */ + void handle_put_data_item(const httplib::Request & req, httplib::Response & res); + + /** + * @brief List data categories (not implemented for ROS 2) + * + * GET /{entities}/{id}/data-categories + * + * Returns 501 Not Implemented. + */ + void handle_data_categories(const httplib::Request & req, httplib::Response & res); + + /** + * @brief List data groups (not implemented for ROS 2) + * + * GET /{entities}/{id}/data-groups + * + * Returns 501 Not Implemented. + */ + void handle_data_groups(const httplib::Request & req, httplib::Response & res); + + private: + HandlerContext & ctx_; +}; + +} // namespace handlers +} // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/discovery/app_handlers.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/discovery/app_handlers.hpp deleted file mode 100644 index 2117faf..0000000 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/discovery/app_handlers.hpp +++ /dev/null @@ -1,155 +0,0 @@ -// 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. - -#ifndef ROS2_MEDKIT_GATEWAY__HTTP__HANDLERS__DISCOVERY__APP_HANDLERS_HPP_ -#define ROS2_MEDKIT_GATEWAY__HTTP__HANDLERS__DISCOVERY__APP_HANDLERS_HPP_ - -#include "ros2_medkit_gateway/http/handlers/handler_context.hpp" - -namespace ros2_medkit_gateway { -namespace handlers { - -/** - * @brief Handlers for app-related REST API endpoints. - * - * Apps represent software applications (typically 1:1 with ROS nodes) - * that provide functionality within the system. - * - * Provides handlers for: - * - GET /apps - List all apps - * - GET /apps/{app-id} - Get app capabilities - * - GET /apps/{app-id}/data - Get app topic data - * - GET /apps/{app-id}/data/{data-id} - Get specific data item - * - GET /apps/{app-id}/operations - List app operations - * - GET /apps/{app-id}/configurations - Get app configurations - * - GET /components/{id}/related-apps - List apps on component - * - * @verifies REQ_DISCOVERY_002 Apps discovery - */ -class AppHandlers { - public: - /** - * @brief Construct app handlers with shared context. - * @param ctx The shared handler context - */ - explicit AppHandlers(HandlerContext & ctx) : ctx_(ctx) { - } - - // ========================================================================= - // Collection endpoints - // ========================================================================= - - /** - * @brief Handle GET /apps - list all apps. - * - * Returns all apps discovered from manifest or runtime. - * In runtime-only mode, returns empty list. - */ - void handle_list_apps(const httplib::Request & req, httplib::Response & res); - - /** - * @brief Handle GET /apps/{app-id} - get app capabilities. - * - * Returns app details with capabilities (data, operations, configurations) - * and HATEOAS links. - */ - void handle_get_app(const httplib::Request & req, httplib::Response & res); - - // ========================================================================= - // App data endpoints - // ========================================================================= - - /** - * @brief Handle GET /apps/{app-id}/data - list app topics. - * - * Returns all topics associated with the app. - */ - void handle_get_app_data(const httplib::Request & req, httplib::Response & res); - - /** - * @brief Handle GET /apps/{app-id}/data/{data-id} - get specific data item. - * - * Returns metadata for a specific topic. - */ - void handle_get_app_data_item(const httplib::Request & req, httplib::Response & res); - - /** - * @brief Handle PUT /apps/{app-id}/data/{data-id} - write data to topic. - * - * Publishes data to the specified topic. - */ - void handle_put_app_data_item(const httplib::Request & req, httplib::Response & res); - - /** - * @brief Handle GET /apps/{app-id}/data-categories - returns 501 Not Implemented. - * - * Data categories are not implemented for ROS 2. - */ - void handle_data_categories(const httplib::Request & req, httplib::Response & res); - - /** - * @brief Handle GET /apps/{app-id}/data-groups - returns 501 Not Implemented. - * - * Data groups are not implemented for ROS 2. - */ - void handle_data_groups(const httplib::Request & req, httplib::Response & res); - - // ========================================================================= - // App operations - // ========================================================================= - - /** - * @brief Handle GET /apps/{app-id}/operations - list app operations. - * - * Returns all services and actions associated with the app. - */ - void handle_list_app_operations(const httplib::Request & req, httplib::Response & res); - - // ========================================================================= - // App configurations - // ========================================================================= - - /** - * @brief Handle GET /apps/{app-id}/configurations - list app parameters. - * - * Returns parameters if app is linked to a runtime node. - */ - void handle_list_app_configurations(const httplib::Request & req, httplib::Response & res); - - // ========================================================================= - // Relationship endpoints - // ========================================================================= - - /** - * @brief Handle GET /components/{id}/related-apps - list apps on component. - */ - void handle_related_apps(const httplib::Request & req, httplib::Response & res); - - /** - * @brief Handle GET /apps/{app-id}/depends-on - list app dependencies. - * - * Returns list of other apps that this app depends on. - * - * @verifies REQ_INTEROP_009 - */ - void handle_get_depends_on(const httplib::Request & req, httplib::Response & res); - - private: - HandlerContext & ctx_; -}; - -} // namespace handlers -} // namespace ros2_medkit_gateway - -#endif // ROS2_MEDKIT_GATEWAY__HTTP__HANDLERS__DISCOVERY__APP_HANDLERS_HPP_ diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/discovery/area_handlers.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/discovery/area_handlers.hpp deleted file mode 100644 index db9e26c..0000000 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/discovery/area_handlers.hpp +++ /dev/null @@ -1,77 +0,0 @@ -// Copyright 2025 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. - -#ifndef ROS2_MEDKIT_GATEWAY__HTTP__HANDLERS__DISCOVERY__AREA_HANDLERS_HPP_ -#define ROS2_MEDKIT_GATEWAY__HTTP__HANDLERS__DISCOVERY__AREA_HANDLERS_HPP_ - -#include "ros2_medkit_gateway/http/handlers/handler_context.hpp" - -namespace ros2_medkit_gateway { -namespace handlers { - -/** - * @brief Handlers for area-related REST API endpoints. - * - * Provides handlers for: - * - GET /areas - List all areas - * - GET /areas/{area_id} - Get a specific area with capabilities - * - GET /areas/{area_id}/components - List components in an area - * - GET /areas/{area_id}/subareas - List nested areas within an area - * - GET /areas/{area_id}/related-components - List components related to area - * - * @verifies REQ_DISCOVERY_004 Entity relationships - */ -class AreaHandlers { - public: - /** - * @brief Construct area handlers with shared context. - * @param ctx The shared handler context - */ - explicit AreaHandlers(HandlerContext & ctx) : ctx_(ctx) { - } - - /** - * @brief Handle GET /areas - list all discovery areas. - */ - void handle_list_areas(const httplib::Request & req, httplib::Response & res); - - /** - * @brief Handle GET /areas/{area_id} - get a specific area with capabilities. - */ - void handle_get_area(const httplib::Request & req, httplib::Response & res); - - /** - * @brief Handle GET /areas/{area_id}/components - list components in area. - */ - void handle_area_components(const httplib::Request & req, httplib::Response & res); - - /** - * @brief Handle GET /areas/{area_id}/subareas - list nested areas. - */ - void handle_get_subareas(const httplib::Request & req, httplib::Response & res); - - /** - * @brief Handle GET /areas/{area_id}/contains - list contained entities (Components). - * @verifies REQ_INTEROP_006 - */ - void handle_get_contains(const httplib::Request & req, httplib::Response & res); - - private: - HandlerContext & ctx_; -}; - -} // namespace handlers -} // namespace ros2_medkit_gateway - -#endif // ROS2_MEDKIT_GATEWAY__HTTP__HANDLERS__DISCOVERY__AREA_HANDLERS_HPP_ diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/discovery/component_handlers.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/discovery/component_handlers.hpp deleted file mode 100644 index 6af2be0..0000000 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/discovery/component_handlers.hpp +++ /dev/null @@ -1,96 +0,0 @@ -// Copyright 2025 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. - -#ifndef ROS2_MEDKIT_GATEWAY__HTTP__HANDLERS__DISCOVERY__COMPONENT_HANDLERS_HPP_ -#define ROS2_MEDKIT_GATEWAY__HTTP__HANDLERS__DISCOVERY__COMPONENT_HANDLERS_HPP_ - -#include "ros2_medkit_gateway/http/handlers/handler_context.hpp" - -namespace ros2_medkit_gateway { -namespace handlers { - -/** - * @brief Handlers for component-related REST API endpoints. - * - * Provides handlers for: - * - GET /components - List all components - * - GET /components/{component_id} - Get a specific component with capabilities - * - GET /components/{component_id}/data - Get all topic data for a component - * - GET /components/{component_id}/data/{topic_name} - Get specific topic data - * - PUT /components/{component_id}/data/{topic_name} - Publish to a topic - * - GET /components/{component_id}/subcomponents - List nested components - * - GET /components/{component_id}/related-apps - List apps on component - * - * @verifies REQ_DISCOVERY_004 Entity relationships - */ -class ComponentHandlers { - public: - /** - * @brief Construct component handlers with shared context. - * @param ctx The shared handler context - */ - explicit ComponentHandlers(HandlerContext & ctx) : ctx_(ctx) { - } - - /** - * @brief Handle GET /components - list all components. - */ - void handle_list_components(const httplib::Request & req, httplib::Response & res); - - /** - * @brief Handle GET /components/{component_id} - get a specific component with capabilities. - */ - void handle_get_component(const httplib::Request & req, httplib::Response & res); - - /** - * @brief Handle GET /components/{component_id}/data - get all topic data. - */ - void handle_component_data(const httplib::Request & req, httplib::Response & res); - - /** - * @brief Handle GET /components/{component_id}/data/{topic_name} - get specific topic. - */ - void handle_component_topic_data(const httplib::Request & req, httplib::Response & res); - - /** - * @brief Handle PUT /components/{component_id}/data/{topic_name} - publish to topic. - */ - void handle_component_topic_publish(const httplib::Request & req, httplib::Response & res); - - /** - * @brief Handle GET /components/{component_id}/subcomponents - list nested components. - */ - void handle_get_subcomponents(const httplib::Request & req, httplib::Response & res); - - /** - - * @brief Handle GET /components/{component_id}/hosts - list Apps hosted on this component. - * @verifies REQ_INTEROP_007 - */ - void handle_get_hosts(const httplib::Request & req, httplib::Response & res); - - /** - * @brief Handle GET /components/{component_id}/depends-on - list component dependencies. - * @verifies REQ_INTEROP_008 - */ - void handle_get_depends_on(const httplib::Request & req, httplib::Response & res); - - private: - HandlerContext & ctx_; -}; - -} // namespace handlers -} // namespace ros2_medkit_gateway - -#endif // ROS2_MEDKIT_GATEWAY__HTTP__HANDLERS__DISCOVERY__COMPONENT_HANDLERS_HPP_ diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/discovery/function_handlers.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/discovery/function_handlers.hpp deleted file mode 100644 index b856f8a..0000000 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/discovery/function_handlers.hpp +++ /dev/null @@ -1,103 +0,0 @@ -// 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. - -#ifndef ROS2_MEDKIT_GATEWAY__HTTP__HANDLERS__DISCOVERY__FUNCTION_HANDLERS_HPP_ -#define ROS2_MEDKIT_GATEWAY__HTTP__HANDLERS__DISCOVERY__FUNCTION_HANDLERS_HPP_ - -#include "ros2_medkit_gateway/http/handlers/handler_context.hpp" - -namespace ros2_medkit_gateway { -namespace handlers { - -/** - * @brief Handlers for function-related REST API endpoints. - * - * Functions are high-level capability groupings (e.g., "navigation", - * "localization") that may be hosted by multiple apps. - * - * Provides handlers for: - * - GET /functions - List all functions - * - GET /functions/{function-id} - Get function capabilities - * - GET /functions/{function-id}/hosts - Get apps that host this function - * - GET /functions/{function-id}/data - Get aggregated function data - * - GET /functions/{function-id}/operations - List function operations - * - * @verifies REQ_DISCOVERY_003 Functions discovery - */ -class FunctionHandlers { - public: - /** - * @brief Construct function handlers with shared context. - * @param ctx The shared handler context - */ - explicit FunctionHandlers(HandlerContext & ctx) : ctx_(ctx) { - } - - // ========================================================================= - // Collection endpoints - // ========================================================================= - - /** - * @brief Handle GET /functions - list all functions. - * - * Returns all functions discovered from manifest. - * In runtime-only mode, returns empty list. - */ - void handle_list_functions(const httplib::Request & req, httplib::Response & res); - - /** - * @brief Handle GET /functions/{function-id} - get function capabilities. - * - * Returns function details with capabilities (hosts, data, operations) - * and HATEOAS links. - */ - void handle_get_function(const httplib::Request & req, httplib::Response & res); - - // ========================================================================= - // Function hosts - // ========================================================================= - - /** - * @brief Handle GET /functions/{function-id}/hosts - get hosts for function. - * - * Returns apps that provide this function. - */ - void handle_function_hosts(const httplib::Request & req, httplib::Response & res); - - // ========================================================================= - // Function data & operations (aggregated from host apps) - // ========================================================================= - - /** - * @brief Handle GET /functions/{function-id}/data - get aggregated data. - * - * Returns topics aggregated from all host apps. - */ - void handle_get_function_data(const httplib::Request & req, httplib::Response & res); - - /** - * @brief Handle GET /functions/{function-id}/operations - list operations. - * - * Returns services and actions aggregated from all host apps. - */ - void handle_list_function_operations(const httplib::Request & req, httplib::Response & res); - - private: - HandlerContext & ctx_; -}; - -} // namespace handlers -} // namespace ros2_medkit_gateway - -#endif // ROS2_MEDKIT_GATEWAY__HTTP__HANDLERS__DISCOVERY__FUNCTION_HANDLERS_HPP_ diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/discovery_handlers.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/discovery_handlers.hpp new file mode 100644 index 0000000..20cc0c0 --- /dev/null +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/discovery_handlers.hpp @@ -0,0 +1,152 @@ +// Copyright 2026 bburda +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#pragma once + +#include + +#include "ros2_medkit_gateway/http/handlers/handler_context.hpp" + +namespace ros2_medkit_gateway { +namespace handlers { + +/** + * @brief Unified handlers for entity discovery REST API endpoints. + * + * Consolidated handlers for discovering and navigating SOVD entities: + * - Areas: ROS 2 namespace groupings + * - Components: Hardware or logical groupings + * - Apps: Software applications (ROS nodes) + * - Functions: Capability abstractions + * + * @verifies REQ_DISCOVERY_001 Areas discovery + * @verifies REQ_DISCOVERY_002 Apps discovery + * @verifies REQ_DISCOVERY_003 Components discovery + * @verifies REQ_DISCOVERY_004 Functions discovery + */ +class DiscoveryHandlers { + public: + /** + * @brief Construct discovery handlers with shared context. + * @param ctx The shared handler context + */ + explicit DiscoveryHandlers(HandlerContext & ctx) : ctx_(ctx) { + } + + // ========================================================================= + // Area endpoints + // ========================================================================= + + /** + * @brief Handle GET /areas - list all areas. + */ + void handle_list_areas(const httplib::Request & req, httplib::Response & res); + + /** + * @brief Handle GET /areas/{area-id} - get area capabilities. + */ + void handle_get_area(const httplib::Request & req, httplib::Response & res); + + /** + * @brief Handle GET /areas/{area-id}/components - list components in area. + */ + void handle_area_components(const httplib::Request & req, httplib::Response & res); + + /** + * @brief Handle GET /areas/{area-id}/subareas - list subareas. + */ + void handle_get_subareas(const httplib::Request & req, httplib::Response & res); + + /** + * @brief Handle GET /areas/{area-id}/contains - SOVD 7.6.2.4 relationship. + * @verifies REQ_INTEROP_006 + */ + void handle_get_contains(const httplib::Request & req, httplib::Response & res); + + // ========================================================================= + // Component endpoints + // ========================================================================= + + /** + * @brief Handle GET /components - list all components. + */ + void handle_list_components(const httplib::Request & req, httplib::Response & res); + + /** + * @brief Handle GET /components/{component-id} - get component capabilities. + */ + void handle_get_component(const httplib::Request & req, httplib::Response & res); + + /** + * @brief Handle GET /components/{id}/subcomponents - list subcomponents. + */ + void handle_get_subcomponents(const httplib::Request & req, httplib::Response & res); + + /** + * @brief Handle GET /components/{id}/hosts - list hosted apps. + * @verifies REQ_INTEROP_007 + */ + void handle_get_hosts(const httplib::Request & req, httplib::Response & res); + + /** + * @brief Handle GET /components/{id}/depends-on - list dependencies. + * @verifies REQ_INTEROP_008 + */ + void handle_component_depends_on(const httplib::Request & req, httplib::Response & res); + + // ========================================================================= + // App endpoints + // ========================================================================= + + /** + * @brief Handle GET /apps - list all apps. + */ + void handle_list_apps(const httplib::Request & req, httplib::Response & res); + + /** + * @brief Handle GET /apps/{app-id} - get app capabilities. + */ + void handle_get_app(const httplib::Request & req, httplib::Response & res); + + /** + * @brief Handle GET /apps/{app-id}/depends-on - list app dependencies. + * @verifies REQ_INTEROP_009 + */ + void handle_app_depends_on(const httplib::Request & req, httplib::Response & res); + + // ========================================================================= + // Function endpoints + // ========================================================================= + + /** + * @brief Handle GET /functions - list all functions. + */ + void handle_list_functions(const httplib::Request & req, httplib::Response & res); + + /** + * @brief Handle GET /functions/{function-id} - get function capabilities. + */ + void handle_get_function(const httplib::Request & req, httplib::Response & res); + + /** + * @brief Handle GET /functions/{function-id}/hosts - list host apps. + */ + void handle_function_hosts(const httplib::Request & req, httplib::Response & res); + + private: + HandlerContext & ctx_; +}; + +} // namespace handlers +} // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/handlers.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/handlers.hpp index 57f2df4..b7d4f8e 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/handlers.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/handlers.hpp @@ -22,11 +22,11 @@ * Include this file to get access to all REST API handlers. */ -// Discovery handlers (areas, components, apps, functions) -#include "ros2_medkit_gateway/http/handlers/discovery/app_handlers.hpp" -#include "ros2_medkit_gateway/http/handlers/discovery/area_handlers.hpp" -#include "ros2_medkit_gateway/http/handlers/discovery/component_handlers.hpp" -#include "ros2_medkit_gateway/http/handlers/discovery/function_handlers.hpp" +// Discovery handlers (unified for all entity types) +#include "ros2_medkit_gateway/http/handlers/discovery_handlers.hpp" + +// Resource handlers (unified across entity types) +#include "ros2_medkit_gateway/http/handlers/data_handlers.hpp" // Other handlers #include "ros2_medkit_gateway/http/handlers/auth_handlers.hpp" diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/http_utils.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/http_utils.hpp index 62dbaf6..c17c379 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/http_utils.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/http_utils.hpp @@ -75,49 +75,4 @@ inline FaultStatusFilter parse_fault_status_param(const httplib::Request & req) return filter; } -/** - * @brief Normalize a ROS2 topic name to a URL-safe SOVD data ID. - * - * Converts topic names like "/sensor/temperature" to "sensor_temperature". - * - Strips leading slash - * - Replaces slashes with underscores - * - * @param topic ROS2 topic name (e.g., "/sensor/temperature") - * @return URL-safe data ID (e.g., "sensor_temperature") - */ -inline std::string normalize_topic_to_id(const std::string & topic) { - std::string result = topic; - // Strip leading slash - if (!result.empty() && result[0] == '/') { - result = result.substr(1); - } - // Replace remaining slashes with underscores - for (auto & c : result) { - if (c == '/') { - c = '_'; - } - } - return result; -} - -/** - * @brief Convert a normalized SOVD data ID back to a ROS2 topic name. - * - * Converts IDs like "sensor_temperature" to "/sensor/temperature". - * Note: This is a best-effort conversion since underscore could be part - * of original topic name. For exact matching, lookups should try both - * the normalized ID and the original topic name. - * - * @param id SOVD data ID (e.g., "sensor_temperature") - * @return ROS2 topic name (e.g., "/sensor_temperature" - keeps underscores) - */ -inline std::string id_to_topic(const std::string & id) { - // Simply prepend slash - don't try to guess where slashes were - // The handler should try matching both normalized ID and original topic - if (id.empty() || id[0] == '/') { - return id; - } - return "/" + id; -} - } // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/rest_server.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/rest_server.hpp index 1234a20..f6620f8 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/rest_server.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/rest_server.hpp @@ -85,10 +85,8 @@ class RESTServer { // Handler context and domain-specific handlers std::unique_ptr handler_ctx_; std::unique_ptr health_handlers_; - std::unique_ptr area_handlers_; - std::unique_ptr component_handlers_; - std::unique_ptr app_handlers_; - std::unique_ptr function_handlers_; + std::unique_ptr discovery_handlers_; + std::unique_ptr data_handlers_; std::unique_ptr operation_handlers_; std::unique_ptr config_handlers_; std::unique_ptr fault_handlers_; 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 ed10cbb..8c23f8b 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 @@ -38,6 +38,32 @@ struct EntityRef { size_t index{0}; }; +/** + * @brief Topic information with direction + */ +struct TopicData { + std::string name; ///< Full topic path (e.g., "/sensor/temperature") + std::string type; ///< Message type (e.g., "std_msgs/msg/Float32") + std::string direction; ///< "publish" | "subscribe" | "both" +}; + +/** + * @brief Aggregated data (topics) result from entity hierarchy + */ +struct AggregatedData { + std::vector topics; + std::vector source_ids; ///< Entity IDs that contributed + std::string aggregation_level; ///< "app" | "component" | "area" | "function" + bool is_aggregated{false}; ///< true if collected from sub-entities + + bool empty() const { + return topics.empty(); + } + size_t total_count() const { + return topics.size(); + } +}; + /** * @brief Aggregated operations result from entity hierarchy */ @@ -123,6 +149,16 @@ class ThreadSafeEntityCache { void update_apps(std::vector apps); void update_functions(std::vector functions); + /** + * @brief Update cached topic type mapping + * + * Called during cache refresh to cache topic name -> message type mapping. + * This avoids expensive ROS graph queries on every /data request. + * + * @param topic_types Map of topic name to message type + */ + void update_topic_types(std::unordered_map topic_types); + // ========================================================================= // Reader methods (shared lock) - called by HTTP handlers // ========================================================================= @@ -145,6 +181,14 @@ class ThreadSafeEntityCache { bool has_app(const std::string & id) const; bool has_function(const std::string & id) const; + // --- Topic type lookup (O(1)) --- + /** + * @brief Get cached message type for a topic + * @param topic_name Full topic path (e.g., "/sensor/temperature") + * @return Message type string, or empty if not cached + */ + std::string get_topic_type(const std::string & topic_name) const; + // --- Resolve any entity by ID --- std::optional find_entity(const std::string & id) const; SovdEntityType get_entity_type(const std::string & id) const; @@ -212,6 +256,47 @@ class ThreadSafeEntityCache { */ AggregatedOperations get_function_operations(const std::string & function_id) const; + // ========================================================================= + // Data aggregation methods (uses relationship indexes) + // ========================================================================= + + /** + * @brief Aggregate data (topics) for any entity by ID + * + * Unified method that works for all entity types. + * Aggregates topics from the entity and its children. + * + * @param entity_id Entity ID to get data for + * @return AggregatedData with topics, or empty if entity not found + */ + AggregatedData get_entity_data(const std::string & entity_id) const; + + /** + * @brief Aggregate data (topics) for an App + */ + AggregatedData get_app_data(const std::string & app_id) const; + + /** + * @brief Aggregate data (topics) for a Component + * + * Returns: Component's own topics + all topics from hosted Apps. + */ + AggregatedData get_component_data(const std::string & component_id) const; + + /** + * @brief Aggregate data (topics) for an Area + * + * Returns: All topics from all Components in the Area. + */ + AggregatedData get_area_data(const std::string & area_id) const; + + /** + * @brief Aggregate data (topics) for a Function + * + * Returns: All topics from all Apps implementing this Function. + */ + AggregatedData get_function_data(const std::string & function_id) const; + // ========================================================================= // Operation lookup (O(1) via operation index) // ========================================================================= @@ -276,6 +361,9 @@ class ThreadSafeEntityCache { // Operation index (operation full_path → owning entity) std::unordered_map operation_index_; + // Topic type cache (topic name → message type) - refreshed periodically + std::unordered_map topic_type_cache_; + // Internal helpers (called under lock) void rebuild_all_indexes(); void rebuild_area_index(); @@ -290,6 +378,14 @@ class ThreadSafeEntityCache { std::unordered_set & seen_paths, AggregatedOperations & result) const; void collect_operations_from_component(size_t comp_index, std::unordered_set & seen_paths, AggregatedOperations & result) const; + + // Data aggregation helpers (called under shared lock) + void collect_topics_from_app(size_t app_index, std::unordered_set & seen_topics, + AggregatedData & result) const; + void collect_topics_from_apps(const std::vector & app_indexes, std::unordered_set & seen_topics, + AggregatedData & result) const; + void collect_topics_from_component(size_t comp_index, std::unordered_set & seen_topics, + AggregatedData & result) const; }; } // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/src/gateway_node.cpp b/src/ros2_medkit_gateway/src/gateway_node.cpp index 9a27b83..33acc1c 100644 --- a/src/ros2_medkit_gateway/src/gateway_node.cpp +++ b/src/ros2_medkit_gateway/src/gateway_node.cpp @@ -322,31 +322,49 @@ void GatewayNode::refresh_cache() { // Discover apps (nodes as Apps when heuristic discovery is enabled) auto apps = discovery_mgr_->discover_apps(); + // Discover functions (from manifest in manifest_only/hybrid mode) + auto functions = discovery_mgr_->discover_functions(); + // Merge both component lists std::vector all_components; all_components.reserve(node_components.size() + topic_components.size()); all_components.insert(all_components.end(), node_components.begin(), node_components.end()); all_components.insert(all_components.end(), topic_components.begin(), topic_components.end()); - auto timestamp = std::chrono::system_clock::now(); - // Capture sizes before move for logging const size_t area_count = areas.size(); const size_t node_component_count = node_components.size(); const size_t topic_component_count = topic_components.size(); const size_t app_count = apps.size(); + const size_t function_count = functions.size(); // Update ThreadSafeEntityCache (primary) with copies // This provides O(1) lookups and proper thread safety thread_safe_cache_.update_all(areas, // copy all_components, // copy apps, // copy - {} // functions - not discovered yet + functions // copy ); - RCLCPP_DEBUG(get_logger(), "Cache refreshed: %zu areas, %zu components (%zu node-based, %zu topic-based), %zu apps", - area_count, node_component_count + topic_component_count, node_component_count, topic_component_count, - app_count); + // Update topic type cache (avoids expensive ROS graph queries on /data requests) + if (data_access_mgr_) { + auto native_sampler = data_access_mgr_->get_native_sampler(); + auto all_topics = native_sampler->discover_all_topics(); + std::unordered_map topic_types; + topic_types.reserve(all_topics.size()); + for (const auto & topic : all_topics) { + if (!topic.type.empty()) { + topic_types[topic.name] = topic.type; + } + } + thread_safe_cache_.update_topic_types(std::move(topic_types)); + } + + RCLCPP_DEBUG( + get_logger(), + "Cache refreshed: %zu areas, %zu components (%zu node-based, %zu topic-based), %zu apps, %zu functions", + area_count, node_component_count + topic_component_count, node_component_count, topic_component_count, + app_count, function_count); } catch (const std::exception & e) { RCLCPP_ERROR(get_logger(), "Failed to refresh cache: %s", e.what()); } catch (...) { diff --git a/src/ros2_medkit_gateway/src/http/handlers/data_handlers.cpp b/src/ros2_medkit_gateway/src/http/handlers/data_handlers.cpp new file mode 100644 index 0000000..78017c2 --- /dev/null +++ b/src/ros2_medkit_gateway/src/http/handlers/data_handlers.cpp @@ -0,0 +1,322 @@ +// Copyright 2026 bburda +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "ros2_medkit_gateway/http/handlers/data_handlers.hpp" + +#include + +#include "ros2_medkit_gateway/exceptions.hpp" +#include "ros2_medkit_gateway/gateway_node.hpp" +#include "ros2_medkit_gateway/http/error_codes.hpp" +#include "ros2_medkit_gateway/http/http_utils.hpp" +#include "ros2_medkit_gateway/http/x_medkit.hpp" + +using json = nlohmann::json; +using httplib::StatusCode; + +namespace ros2_medkit_gateway { +namespace handlers { + +void DataHandlers::handle_list_data(const httplib::Request & req, httplib::Response & res) { + std::string entity_id; + try { + if (req.matches.size() < 2) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); + return; + } + + entity_id = req.matches[1]; + + auto validation_result = ctx_.validate_entity_id(entity_id); + if (!validation_result) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid entity ID", + {{"details", validation_result.error()}, {"entity_id", entity_id}}); + return; + } + + // First, verify that the entity actually exists in the cache + const auto & cache = ctx_.node()->get_thread_safe_cache(); + auto entity_ref = cache.find_entity(entity_id); + if (!entity_ref) { + HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Entity not found", + {{"entity_id", entity_id}}); + return; + } + + // Use unified cache method to get aggregated data + auto aggregated = cache.get_entity_data(entity_id); + + // Get data access manager for type introspection + auto data_access_mgr = ctx_.node()->get_data_access_manager(); + auto type_introspection = data_access_mgr->get_type_introspection(); + + // Build items array with ValueMetadata format + json items = json::array(); + + for (const auto & topic : aggregated.topics) { + json item; + // SOVD required fields - use topic.name directly as ID (clients URL-encode for GET/PUT) + item["id"] = topic.name; + item["name"] = topic.name; + item["category"] = "currentData"; + + // x-medkit extension for ROS2-specific data + XMedkit ext; + ext.ros2_topic(topic.name).add_ros2("direction", topic.direction); + + // Add type info if available (use cached topic types for O(1) lookup) + std::string topic_type = cache.get_topic_type(topic.name); + if (!topic_type.empty()) { + ext.ros2_type(topic_type); + try { + auto type_info = type_introspection->get_type_info(topic_type); + ext.type_info(type_info.schema); + } catch (const std::exception & e) { + RCLCPP_DEBUG(HandlerContext::logger(), "Could not get type info for topic '%s': %s", topic.name.c_str(), + e.what()); + } + } + + item["x-medkit"] = ext.build(); + items.push_back(item); + } + + // Build response with x-medkit for total_count + json response; + response["items"] = items; + + XMedkit resp_ext; + resp_ext.entity_id(entity_id).add("total_count", items.size()); + if (aggregated.is_aggregated) { + resp_ext.add("aggregated_from", aggregated.source_ids); + resp_ext.add("aggregation_level", aggregated.aggregation_level); + } + response["x-medkit"] = resp_ext.build(); + + HandlerContext::send_json(res, response); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, + "Failed to retrieve entity data", {{"details", e.what()}, {"entity_id", entity_id}}); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_list_data for entity '%s': %s", entity_id.c_str(), + e.what()); + } +} + +void DataHandlers::handle_get_data_item(const httplib::Request & req, httplib::Response & res) { + std::string entity_id; + std::string topic_name; + try { + if (req.matches.size() < 3) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); + return; + } + + entity_id = req.matches[1]; + // cpp-httplib automatically decodes percent-encoded characters in URL path + topic_name = req.matches[2]; + + auto validation_result = ctx_.validate_entity_id(entity_id); + if (!validation_result) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid entity ID", + {{"details", validation_result.error()}, {"entity_id", entity_id}}); + return; + } + + // Verify entity exists + const auto & cache = ctx_.node()->get_thread_safe_cache(); + auto entity_ref = cache.find_entity(entity_id); + if (!entity_ref) { + HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Entity not found", + {{"entity_id", entity_id}}); + return; + } + + // Determine the full ROS topic path + std::string full_topic_path; + if (topic_name.empty() || topic_name[0] == '/') { + full_topic_path = topic_name; + } else { + full_topic_path = "/" + topic_name; + } + + // Get topic data from DataAccessManager + auto data_access_mgr = ctx_.node()->get_data_access_manager(); + auto native_sampler = data_access_mgr->get_native_sampler(); + auto sample = native_sampler->sample_topic(full_topic_path, data_access_mgr->get_topic_sample_timeout()); + + // Build SOVD ReadValue response (id must match what list returns for round-trip) + json response; + response["id"] = full_topic_path; + + // SOVD "data" field contains the actual value + if (sample.has_data && sample.data) { + response["data"] = *sample.data; + } else { + response["data"] = json::object(); + } + + // Build x-medkit extension with ROS2-specific data + XMedkit ext; + ext.ros2_topic(full_topic_path).entity_id(entity_id); + if (!sample.message_type.empty()) { + ext.ros2_type(sample.message_type); + + // Add type_info schema for the message type + auto type_introspection = data_access_mgr->get_type_introspection(); + try { + auto type_info = type_introspection->get_type_info(sample.message_type); + ext.type_info(type_info.schema); + } catch (const std::exception & e) { + RCLCPP_DEBUG(HandlerContext::logger(), "Could not get type info for topic '%s': %s", full_topic_path.c_str(), + e.what()); + } + } + ext.add("timestamp", sample.timestamp_ns); + ext.add("publisher_count", sample.publisher_count); + ext.add("subscriber_count", sample.subscriber_count); + ext.add("status", sample.has_data ? "data" : "metadata_only"); + response["x-medkit"] = ext.build(); + + HandlerContext::send_json(res, response); + } catch (const TopicNotAvailableException & e) { + HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_X_MEDKIT_ROS2_TOPIC_UNAVAILABLE, "Topic not found", + {{"entity_id", entity_id}, {"topic_name", topic_name}}); + RCLCPP_DEBUG(HandlerContext::logger(), "Topic not available for entity '%s', topic '%s': %s", entity_id.c_str(), + topic_name.c_str(), e.what()); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, + "Failed to retrieve topic data", + {{"details", e.what()}, {"entity_id", entity_id}, {"topic_name", topic_name}}); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_data_item for entity '%s', topic '%s': %s", + entity_id.c_str(), topic_name.c_str(), e.what()); + } +} + +void DataHandlers::handle_put_data_item(const httplib::Request & req, httplib::Response & res) { + std::string entity_id; + std::string topic_name; + try { + if (req.matches.size() < 3) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); + return; + } + + entity_id = req.matches[1]; + topic_name = req.matches[2]; + + auto validation_result = ctx_.validate_entity_id(entity_id); + if (!validation_result) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid entity ID", + {{"details", validation_result.error()}, {"entity_id", entity_id}}); + return; + } + + // Parse request body + json body; + try { + body = json::parse(req.body); + } catch (const json::parse_error & e) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid JSON in request body", + {{"details", e.what()}}); + return; + } + + // Validate required fields: type and data + if (!body.contains("type") || !body["type"].is_string()) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, + "Missing or invalid 'type' field", + {{"details", "Request body must contain 'type' string field"}}); + return; + } + + if (!body.contains("data")) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Missing 'data' field", + {{"details", "Request body must contain 'data' field"}}); + return; + } + + std::string msg_type = body["type"].get(); + json data = body["data"]; + + // Validate message type format (e.g., std_msgs/msg/Float32) + size_t slash_count = std::count(msg_type.begin(), msg_type.end(), '/'); + size_t msg_pos = msg_type.find("/msg/"); + bool valid_format = + (slash_count == 2) && (msg_pos != std::string::npos) && (msg_pos > 0) && (msg_pos + 5 < msg_type.length()); + + if (!valid_format) { + HandlerContext::send_error( + res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid message type format", + {{"details", "Message type should be in format: package/msg/Type"}, {"type", msg_type}}); + return; + } + + // Verify entity exists + const auto & cache = ctx_.node()->get_thread_safe_cache(); + auto entity_ref = cache.find_entity(entity_id); + if (!entity_ref) { + HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Entity not found", + {{"entity_id", entity_id}}); + return; + } + + // Build full topic path (mirror GET logic: only prefix '/' when needed) + std::string full_topic_path = topic_name; + if (!full_topic_path.empty() && full_topic_path.front() != '/') { + full_topic_path = "/" + full_topic_path; + } + + // Publish data using DataAccessManager + auto data_access_mgr = ctx_.node()->get_data_access_manager(); + json result = data_access_mgr->publish_to_topic(full_topic_path, msg_type, data); + + // Build response with x-medkit extension (id must match what list returns for round-trip) + json response; + response["id"] = full_topic_path; + response["data"] = data; // Echo back the written data + + XMedkit ext; + ext.ros2_topic(full_topic_path).ros2_type(msg_type).entity_id(entity_id); + if (result.contains("status")) { + ext.add("status", result["status"]); + } + if (result.contains("publisher_created")) { + ext.add("publisher_created", result["publisher_created"]); + } + response["x-medkit"] = ext.build(); + + HandlerContext::send_json(res, response); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, + "Failed to publish to topic", + {{"details", e.what()}, {"entity_id", entity_id}, {"topic_name", topic_name}}); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_put_data_item for entity '%s', topic '%s': %s", + entity_id.c_str(), topic_name.c_str(), e.what()); + } +} + +void DataHandlers::handle_data_categories(const httplib::Request & req, httplib::Response & res) { + (void)req; + HandlerContext::send_error(res, StatusCode::NotImplemented_501, ERR_NOT_IMPLEMENTED, + "Data categories are not implemented for ROS 2", {{"feature", "data-categories"}}); +} + +void DataHandlers::handle_data_groups(const httplib::Request & req, httplib::Response & res) { + (void)req; + HandlerContext::send_error(res, StatusCode::NotImplemented_501, ERR_NOT_IMPLEMENTED, + "Data groups are not implemented for ROS 2", {{"feature", "data-groups"}}); +} + +} // namespace handlers +} // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/src/http/handlers/discovery/app_handlers.cpp b/src/ros2_medkit_gateway/src/http/handlers/discovery/app_handlers.cpp deleted file mode 100644 index 4a08b8f..0000000 --- a/src/ros2_medkit_gateway/src/http/handlers/discovery/app_handlers.cpp +++ /dev/null @@ -1,701 +0,0 @@ -// Copyright 2026 bburda -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "ros2_medkit_gateway/http/handlers/discovery/app_handlers.hpp" - -#include "ros2_medkit_gateway/gateway_node.hpp" -#include "ros2_medkit_gateway/http/error_codes.hpp" -#include "ros2_medkit_gateway/http/handlers/capability_builder.hpp" -#include "ros2_medkit_gateway/http/http_utils.hpp" -#include "ros2_medkit_gateway/http/x_medkit.hpp" - -using json = nlohmann::json; -using httplib::StatusCode; - -namespace ros2_medkit_gateway { -namespace handlers { - -void AppHandlers::handle_list_apps(const httplib::Request & req, httplib::Response & res) { - (void)req; // Unused parameter - - try { - auto discovery = ctx_.node()->get_discovery_manager(); - auto apps = discovery->discover_apps(); - - // Build items array with EntityReference format - json items = json::array(); - for (const auto & app : apps) { - json app_item; - // SOVD required fields for EntityReference - app_item["id"] = app.id; - app_item["name"] = app.name.empty() ? app.id : app.name; - app_item["href"] = "/api/v1/apps/" + app.id; - - // Optional SOVD fields - if (!app.description.empty()) { - app_item["description"] = app.description; - } - if (!app.tags.empty()) { - app_item["tags"] = app.tags; - } - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.source(app.source).is_online(app.is_online); - if (!app.component_id.empty()) { - ext.component_id(app.component_id); - } - if (app.bound_fqn) { - ext.ros2_node(*app.bound_fqn); - } - app_item["x-medkit"] = ext.build(); - - items.push_back(app_item); - } - - json response; - response["items"] = items; - - // x-medkit for response-level metadata - XMedkit resp_ext; - resp_ext.add("total_count", items.size()); - response["x-medkit"] = resp_ext.build(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_list_apps: %s", e.what()); - } -} - -void AppHandlers::handle_get_app(const httplib::Request & req, httplib::Response & res) { - try { - // Extract app_id from URL path - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string app_id = req.matches[1]; - - // Validate app_id - auto validation_result = ctx_.validate_entity_id(app_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid app ID", - {{"details", validation_result.error()}, {"app_id", app_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto app_opt = discovery->get_app(app_id); - - if (!app_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "App not found", - {{"app_id", app_id}}); - return; - } - - const auto & app = *app_opt; - - // Build response with structure - json response; - response["id"] = app.id; - response["name"] = app.name; - - if (!app.description.empty()) { - response["description"] = app.description; - } - if (!app.translation_id.empty()) { - response["translation_id"] = app.translation_id; - } - if (!app.tags.empty()) { - response["tags"] = app.tags; - } - - // SOVD capability URIs as flat fields at top level - std::string base_uri = "/api/v1/apps/" + app.id; - response["data"] = base_uri + "/data"; - response["operations"] = base_uri + "/operations"; - response["configurations"] = base_uri + "/configurations"; - response["faults"] = base_uri + "/faults"; // Apps also support faults - - // Add is-located-on reference to hosting Component (SOVD 7.6.3) - if (!app.component_id.empty()) { - response["is-located-on"] = "/api/v1/components/" + app.component_id; - } - - // Add depends-on only when app has dependencies - if (!app.depends_on.empty()) { - response["depends-on"] = base_uri + "/depends-on"; - } - - // Build capabilities using CapabilityBuilder (for capability introspection) - using Cap = CapabilityBuilder::Capability; - std::vector caps = {Cap::DATA, Cap::OPERATIONS, Cap::CONFIGURATIONS}; - response["capabilities"] = CapabilityBuilder::build_capabilities("apps", app.id, caps); - - // Build HATEOAS links using LinksBuilder - LinksBuilder links; - links.self("/api/v1/apps/" + app.id).collection("/api/v1/apps"); - if (!app.component_id.empty()) { - links.add("is-located-on", "/api/v1/components/" + app.component_id); - } - response["_links"] = links.build(); - - // Add depends-on as array if present (special case - multiple links) - if (!app.depends_on.empty()) { - json depends_links = json::array(); - for (const auto & dep_id : app.depends_on) { - depends_links.push_back("/api/v1/apps/" + dep_id); - } - response["_links"]["depends-on"] = depends_links; - } - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.source(app.source).is_online(app.is_online); - if (app.bound_fqn) { - ext.ros2_node(*app.bound_fqn); - } - if (!app.component_id.empty()) { - ext.component_id(app.component_id); - } - response["x-medkit"] = ext.build(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_app: %s", e.what()); - } -} - -void AppHandlers::handle_get_app_data(const httplib::Request & req, httplib::Response & res) { - try { - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string app_id = req.matches[1]; - - auto validation_result = ctx_.validate_entity_id(app_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid app ID", - {{"details", validation_result.error()}, {"app_id", app_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto app_opt = discovery->get_app(app_id); - - if (!app_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "App not found", - {{"app_id", app_id}}); - return; - } - - const auto & app = *app_opt; - - // Build data items from app's topics - json items = json::array(); - - // Publishers - category "currentData" - for (const auto & topic_name : app.topics.publishes) { - json item; - // Required fields - item["id"] = normalize_topic_to_id(topic_name); - item["name"] = topic_name; // Use topic name as display name - item["category"] = "currentData"; - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.ros2_topic(topic_name).add_ros2("direction", "publish"); - item["x-medkit"] = ext.build(); - - items.push_back(item); - } - - // Subscribers - category "currentData" - for (const auto & topic_name : app.topics.subscribes) { - json item; - // Required fields - item["id"] = normalize_topic_to_id(topic_name); - item["name"] = topic_name; - item["category"] = "currentData"; - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.ros2_topic(topic_name).add_ros2("direction", "subscribe"); - item["x-medkit"] = ext.build(); - - items.push_back(item); - } - - // Build response with x-medkit for total_count - json response; - response["items"] = items; - - XMedkit resp_ext; - resp_ext.entity_id(app_id).add("total_count", items.size()); - response["x-medkit"] = resp_ext.build(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_app_data: %s", e.what()); - } -} - -void AppHandlers::handle_get_app_data_item(const httplib::Request & req, httplib::Response & res) { - try { - if (req.matches.size() < 3) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string app_id = req.matches[1]; - std::string data_id = req.matches[2]; - - auto validation_result = ctx_.validate_entity_id(app_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid app ID", - {{"details", validation_result.error()}, {"app_id", app_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto app_opt = discovery->get_app(app_id); - - if (!app_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "App not found", - {{"app_id", app_id}}); - return; - } - - const auto & app = *app_opt; - - // Get data access manager for topic sampling - auto data_access_mgr = ctx_.node()->get_data_access_manager(); - auto native_sampler = data_access_mgr->get_native_sampler(); - - // Helper lambda to build SOVD ReadValue response - auto build_data_response = [&](const std::string & topic_name, const std::string & direction) { - json response; - // SOVD required fields - response["id"] = normalize_topic_to_id(topic_name); - - // Sample topic value via native sampler - auto sample = native_sampler->sample_topic(topic_name, data_access_mgr->get_topic_sample_timeout()); - - // SOVD "data" field contains the actual value - if (sample.has_data && sample.data) { - response["data"] = *sample.data; - } else { - response["data"] = json::object(); // Empty object if no data available - } - - // Build x-medkit extension with ROS2-specific data - XMedkit ext; - ext.ros2_topic(topic_name).add_ros2("direction", direction); - if (!sample.message_type.empty()) { - ext.ros2_type(sample.message_type); - } - ext.add("timestamp", sample.timestamp_ns); - ext.add("publisher_count", sample.publisher_count); - ext.add("subscriber_count", sample.subscriber_count); - ext.add("status", sample.has_data ? "data" : "metadata_only"); - response["x-medkit"] = ext.build(); - - return response; - }; - - // Try matching by normalized ID or original topic name - // Search in publishers - for (const auto & topic_name : app.topics.publishes) { - if (normalize_topic_to_id(topic_name) == data_id || topic_name == data_id) { - HandlerContext::send_json(res, build_data_response(topic_name, "publish")); - return; - } - } - - // Search in subscribers - for (const auto & topic_name : app.topics.subscribes) { - if (normalize_topic_to_id(topic_name) == data_id || topic_name == data_id) { - HandlerContext::send_json(res, build_data_response(topic_name, "subscribe")); - return; - } - } - - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_RESOURCE_NOT_FOUND, "Data item not found", - {{"app_id", app_id}, {"data_id", data_id}}); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_app_data_item: %s", e.what()); - } -} - -void AppHandlers::handle_list_app_operations(const httplib::Request & req, httplib::Response & res) { - try { - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string app_id = req.matches[1]; - - auto validation_result = ctx_.validate_entity_id(app_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid app ID", - {{"details", validation_result.error()}, {"app_id", app_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto app_opt = discovery->get_app(app_id); - - if (!app_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "App not found", - {{"app_id", app_id}}); - return; - } - - const auto & app = *app_opt; - - json items = json::array(); - - // Add services - for (const auto & svc : app.services) { - json item; - item["id"] = svc.name; - item["name"] = svc.name; - item["type"] = "service"; - item["service_type"] = svc.type; - items.push_back(item); - } - - // Add actions - for (const auto & act : app.actions) { - json item; - item["id"] = act.name; - item["name"] = act.name; - item["type"] = "action"; - item["action_type"] = act.type; - items.push_back(item); - } - - json response; - response["items"] = items; - response["total_count"] = items.size(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_list_app_operations: %s", e.what()); - } -} - -void AppHandlers::handle_list_app_configurations(const httplib::Request & req, httplib::Response & res) { - try { - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string app_id = req.matches[1]; - - auto validation_result = ctx_.validate_entity_id(app_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid app ID", - {{"details", validation_result.error()}, {"app_id", app_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto app_opt = discovery->get_app(app_id); - - if (!app_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "App not found", - {{"app_id", app_id}}); - return; - } - - const auto & app = *app_opt; - - json response; - json items = json::array(); - - // If app is linked to a runtime node, fetch parameters from it - if (app.bound_fqn) { - auto config_mgr = ctx_.node()->get_configuration_manager(); - auto result = config_mgr->list_parameters(*app.bound_fqn); - - if (result.success && result.data.is_array()) { - for (const auto & param : result.data) { - json item; - item["id"] = param["name"]; - item["name"] = param["name"]; - item["value"] = param["value"]; - item["type"] = param["type"]; - items.push_back(item); - } - } - response["bound_node"] = *app.bound_fqn; - } - - response["items"] = items; - response["total_count"] = items.size(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_list_app_configurations: %s", e.what()); - } -} - -void AppHandlers::handle_related_apps(const httplib::Request & req, httplib::Response & res) { - try { - // Extract component_id from URL path - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string component_id = req.matches[1]; - - // Validate component_id - auto validation_result = ctx_.validate_entity_id(component_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid component ID", - {{"details", validation_result.error()}, {"component_id", component_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto apps = discovery->get_apps_for_component(component_id); - - json items = json::array(); - for (const auto & app : apps) { - json app_item; - app_item["id"] = app.id; - app_item["name"] = app.name; - if (!app.description.empty()) { - app_item["description"] = app.description; - } - if (app.is_online) { - app_item["is_online"] = true; - } - app_item["_links"] = {{"self", {{"href", "/api/v1/apps/" + app.id}}}}; - items.push_back(app_item); - } - - json response; - response["items"] = items; - response["total_count"] = apps.size(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_related_apps: %s", e.what()); - } -} - -void AppHandlers::handle_get_depends_on(const httplib::Request & req, httplib::Response & res) { - try { - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string app_id = req.matches[1]; - - auto validation_result = ctx_.validate_entity_id(app_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid app ID", - {{"details", validation_result.error()}, {"app_id", app_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto app_opt = discovery->get_app(app_id); - - if (!app_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "App not found", - {{"app_id", app_id}}); - return; - } - - const auto & app = *app_opt; - - // Build list of dependency references - json items = json::array(); - for (const auto & dep_id : app.depends_on) { - json item; - item["id"] = dep_id; - item["href"] = "/api/v1/apps/" + dep_id; - - // Try to get the dependency app for additional info - auto dep_opt = discovery->get_app(dep_id); - if (dep_opt) { - item["name"] = dep_opt->name.empty() ? dep_id : dep_opt->name; - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.source(dep_opt->source).is_online(dep_opt->is_online); - item["x-medkit"] = ext.build(); - } else { - // Dependency app could not be resolved; mark as missing in x-medkit - item["name"] = dep_id; - XMedkit ext; - ext.add("missing", true); - item["x-medkit"] = ext.build(); - RCLCPP_WARN(HandlerContext::logger(), "App '%s' declares dependency on unknown app '%s'", app_id.c_str(), - dep_id.c_str()); - } - - items.push_back(item); - } - - json response; - response["items"] = items; - - // x-medkit for response-level metadata - XMedkit resp_ext; - resp_ext.add("total_count", items.size()); - response["x-medkit"] = resp_ext.build(); - - // HATEOAS links - json links; - links["self"] = "/api/v1/apps/" + app_id + "/depends-on"; - links["app"] = "/api/v1/apps/" + app_id; - response["_links"] = links; - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_depends_on: %s", e.what()); - } -} - -void AppHandlers::handle_put_app_data_item(const httplib::Request & req, httplib::Response & res) { - std::string app_id; - std::string topic_name; - try { - if (req.matches.size() < 3) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - app_id = req.matches[1]; - topic_name = req.matches[2]; - - auto app_validation = ctx_.validate_entity_id(app_id); - if (!app_validation) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid app ID", - {{"details", app_validation.error()}, {"app_id", app_id}}); - return; - } - - json body; - try { - body = json::parse(req.body); - } catch (const json::parse_error & e) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid JSON in request body", - {{"details", e.what()}}); - return; - } - - if (!body.contains("type") || !body["type"].is_string()) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, - "Missing or invalid 'type' field", - {{"details", "Request body must contain 'type' string field"}}); - return; - } - - if (!body.contains("data")) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Missing 'data' field", - {{"details", "Request body must contain 'data' field"}}); - return; - } - - std::string msg_type = body["type"].get(); - json data = body["data"]; - - size_t slash_count = std::count(msg_type.begin(), msg_type.end(), '/'); - size_t msg_pos = msg_type.find("/msg/"); - bool valid_format = - (slash_count == 2) && (msg_pos != std::string::npos) && (msg_pos > 0) && (msg_pos + 5 < msg_type.length()); - - if (!valid_format) { - HandlerContext::send_error( - res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid message type format", - {{"details", "Message type should be in format: package/msg/Type"}, {"type", msg_type}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto app_opt = discovery->get_app(app_id); - - if (!app_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "App not found", - {{"app_id", app_id}}); - return; - } - - std::string full_topic_path = "/" + topic_name; - - auto data_access_mgr = ctx_.node()->get_data_access_manager(); - json result = data_access_mgr->publish_to_topic(full_topic_path, msg_type, data); - - json response; - response["id"] = normalize_topic_to_id(full_topic_path); - response["data"] = data; - - XMedkit ext; - ext.ros2_topic(full_topic_path).ros2_type(msg_type).entity_id(app_id); - if (result.contains("status")) { - ext.add("status", result["status"]); - } - response["x-medkit"] = ext.build(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, - "Failed to publish to topic", - {{"details", e.what()}, {"app_id", app_id}, {"topic_name", topic_name}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_put_app_data_item: %s", e.what()); - } -} - -void AppHandlers::handle_data_categories(const httplib::Request & req, httplib::Response & res) { - (void)req; - HandlerContext::send_error(res, StatusCode::NotImplemented_501, ERR_NOT_IMPLEMENTED, - "Data categories are not implemented for ROS 2", {{"feature", "data-categories"}}); -} - -void AppHandlers::handle_data_groups(const httplib::Request & req, httplib::Response & res) { - (void)req; - HandlerContext::send_error(res, StatusCode::NotImplemented_501, ERR_NOT_IMPLEMENTED, - "Data groups are not implemented for ROS 2", {{"feature", "data-groups"}}); -} - -} // namespace handlers -} // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/src/http/handlers/discovery/area_handlers.cpp b/src/ros2_medkit_gateway/src/http/handlers/discovery/area_handlers.cpp deleted file mode 100644 index 6fdfdc8..0000000 --- a/src/ros2_medkit_gateway/src/http/handlers/discovery/area_handlers.cpp +++ /dev/null @@ -1,357 +0,0 @@ -// Copyright 2025 bburda -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "ros2_medkit_gateway/http/handlers/discovery/area_handlers.hpp" - -#include "ros2_medkit_gateway/gateway_node.hpp" -#include "ros2_medkit_gateway/http/error_codes.hpp" -#include "ros2_medkit_gateway/http/handlers/capability_builder.hpp" -#include "ros2_medkit_gateway/http/x_medkit.hpp" - -using json = nlohmann::json; -using httplib::StatusCode; - -namespace ros2_medkit_gateway { -namespace handlers { - -void AreaHandlers::handle_list_areas(const httplib::Request & req, httplib::Response & res) { - (void)req; // Unused parameter - - try { - const auto & cache = ctx_.node()->get_thread_safe_cache(); - const auto areas = cache.get_areas(); - - // Build items array with EntityReference format - json items = json::array(); - for (const auto & area : areas) { - json area_item; - // Required fields for EntityReference - area_item["id"] = area.id; - area_item["name"] = area.name.empty() ? area.id : area.name; - area_item["href"] = "/api/v1/areas/" + area.id; - - // Optional fields - if (!area.description.empty()) { - area_item["description"] = area.description; - } - if (!area.tags.empty()) { - area_item["tags"] = area.tags; - } - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.ros2_namespace(area.namespace_path); - if (!area.parent_area_id.empty()) { - ext.add("parent_area_id", area.parent_area_id); - } - area_item["x-medkit"] = ext.build(); - - items.push_back(area_item); - } - - json response; - response["items"] = items; - - // x-medkit for response-level metadata - XMedkit resp_ext; - resp_ext.add("total_count", items.size()); - response["x-medkit"] = resp_ext.build(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error"); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_list_areas: %s", e.what()); - } -} - -void AreaHandlers::handle_get_area(const httplib::Request & req, httplib::Response & res) { - try { - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string area_id = req.matches[1]; - - auto validation_result = ctx_.validate_entity_id(area_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid area ID", - {{"details", validation_result.error()}, {"area_id", area_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto area_opt = discovery->get_area(area_id); - - if (!area_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Area not found", - {{"area_id", area_id}}); - return; - } - - const auto & area = *area_opt; - - // Build response - json response; - response["id"] = area.id; - response["name"] = area.name.empty() ? area.id : area.name; - - if (!area.description.empty()) { - response["description"] = area.description; - } - if (!area.tags.empty()) { - response["tags"] = area.tags; - } - - // Capability URIs as flat fields at top level - std::string base_uri = "/api/v1/areas/" + area.id; - response["subareas"] = base_uri + "/subareas"; - response["components"] = base_uri + "/components"; - response["contains"] = base_uri + "/contains"; // SOVD 7.6.2.4 - - // Build capabilities for areas - using Cap = CapabilityBuilder::Capability; - std::vector caps = {Cap::SUBAREAS, Cap::CONTAINS}; - response["capabilities"] = CapabilityBuilder::build_capabilities("areas", area.id, caps); - - // Build HATEOAS links - LinksBuilder links; - links.self("/api/v1/areas/" + area.id).collection("/api/v1/areas"); - if (!area.parent_area_id.empty()) { - links.parent("/api/v1/areas/" + area.parent_area_id); - } - response["_links"] = links.build(); - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.ros2_namespace(area.namespace_path); - if (!area.parent_area_id.empty()) { - ext.add("parent_area_id", area.parent_area_id); - } - response["x-medkit"] = ext.build(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_area: %s", e.what()); - } -} - -void AreaHandlers::handle_area_components(const httplib::Request & req, httplib::Response & res) { - try { - // Extract area_id from URL path - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string area_id = req.matches[1]; - - // Validate area_id - auto validation_result = ctx_.validate_entity_id(area_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid area ID", - {{"details", validation_result.error()}, {"area_id", area_id}}); - return; - } - - const auto & cache = ctx_.node()->get_thread_safe_cache(); - - // Check if area exists (O(1) lookup) - if (!cache.has_area(area_id)) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Area not found", - {{"area_id", area_id}}); - return; - } - - // Filter components by area - const auto components = cache.get_components(); - json items = json::array(); - for (const auto & component : components) { - if (component.area == area_id) { - json comp_item; - // SOVD required fields for EntityReference - comp_item["id"] = component.id; - comp_item["name"] = component.name.empty() ? component.id : component.name; - comp_item["href"] = "/api/v1/components/" + component.id; - - // Optional SOVD fields - if (!component.description.empty()) { - comp_item["description"] = component.description; - } - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.source(component.source); - if (!component.namespace_path.empty()) { - ext.ros2_namespace(component.namespace_path); - } - comp_item["x-medkit"] = ext.build(); - - items.push_back(comp_item); - } - } - - json response; - response["items"] = items; - - // x-medkit for response-level metadata - XMedkit resp_ext; - resp_ext.add("total_count", items.size()); - response["x-medkit"] = resp_ext.build(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error"); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_area_components: %s", e.what()); - } -} - -void AreaHandlers::handle_get_subareas(const httplib::Request & req, httplib::Response & res) { - try { - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string area_id = req.matches[1]; - - auto validation_result = ctx_.validate_entity_id(area_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid area ID", - {{"details", validation_result.error()}, {"area_id", area_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto area_opt = discovery->get_area(area_id); - - if (!area_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Area not found", - {{"area_id", area_id}}); - return; - } - - // Get subareas - auto subareas = discovery->get_subareas(area_id); - - json items = json::array(); - for (const auto & subarea : subareas) { - json item; - item["id"] = subarea.id; - item["name"] = subarea.name.empty() ? subarea.id : subarea.name; - item["href"] = "/api/v1/areas/" + subarea.id; - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.ros2_namespace(subarea.namespace_path); - item["x-medkit"] = ext.build(); - - items.push_back(item); - } - - json response; - response["items"] = items; - - // x-medkit for response-level metadata - XMedkit resp_ext; - resp_ext.add("total_count", items.size()); - response["x-medkit"] = resp_ext.build(); - - // HATEOAS links - json links; - links["self"] = "/api/v1/areas/" + area_id + "/subareas"; - links["parent"] = "/api/v1/areas/" + area_id; - response["_links"] = links; - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_subareas: %s", e.what()); - } -} - -void AreaHandlers::handle_get_contains(const httplib::Request & req, httplib::Response & res) { - // @verifies REQ_INTEROP_006 - try { - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string area_id = req.matches[1]; - - auto validation_result = ctx_.validate_entity_id(area_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid area ID", - {{"details", validation_result.error()}, {"area_id", area_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto area_opt = discovery->get_area(area_id); - - if (!area_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Area not found", - {{"area_id", area_id}}); - return; - } - - // Get components for this area (SOVD 7.6.2.4 - non-deprecated relationship) - auto components = discovery->get_components_for_area(area_id); - - json items = json::array(); - for (const auto & comp : components) { - json item; - item["id"] = comp.id; - item["name"] = comp.name.empty() ? comp.id : comp.name; - item["href"] = "/api/v1/components/" + comp.id; - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.source(comp.source); - if (!comp.namespace_path.empty()) { - ext.ros2_namespace(comp.namespace_path); - } - item["x-medkit"] = ext.build(); - - items.push_back(item); - } - - json response; - response["items"] = items; - - // x-medkit for response-level metadata - XMedkit resp_ext; - resp_ext.add("total_count", items.size()); - response["x-medkit"] = resp_ext.build(); - - // HATEOAS links - json links; - links["self"] = "/api/v1/areas/" + area_id + "/contains"; - links["area"] = "/api/v1/areas/" + area_id; - response["_links"] = links; - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_contains: %s", e.what()); - } -} - -} // namespace handlers -} // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/src/http/handlers/discovery/component_handlers.cpp b/src/ros2_medkit_gateway/src/http/handlers/discovery/component_handlers.cpp deleted file mode 100644 index 4de8463..0000000 --- a/src/ros2_medkit_gateway/src/http/handlers/discovery/component_handlers.cpp +++ /dev/null @@ -1,722 +0,0 @@ -// Copyright 2025 bburda -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "ros2_medkit_gateway/http/handlers/discovery/component_handlers.hpp" - -#include -#include - -#include "ros2_medkit_gateway/exceptions.hpp" -#include "ros2_medkit_gateway/gateway_node.hpp" -#include "ros2_medkit_gateway/http/error_codes.hpp" -#include "ros2_medkit_gateway/http/handlers/capability_builder.hpp" -#include "ros2_medkit_gateway/http/http_utils.hpp" -#include "ros2_medkit_gateway/http/x_medkit.hpp" - -using json = nlohmann::json; -using httplib::StatusCode; - -namespace ros2_medkit_gateway { -namespace handlers { - -void ComponentHandlers::handle_list_components(const httplib::Request & req, httplib::Response & res) { - (void)req; // Unused parameter - - try { - const auto & cache = ctx_.node()->get_thread_safe_cache(); - const auto components = cache.get_components(); - - // Build items array with EntityReference format - json items = json::array(); - for (const auto & component : components) { - json item; - // Required fields for EntityReference - item["id"] = component.id; - item["name"] = component.name.empty() ? component.id : component.name; - item["href"] = "/api/v1/components/" + component.id; - - // Optional fields - if (!component.description.empty()) { - item["description"] = component.description; - } - if (!component.tags.empty()) { - item["tags"] = component.tags; - } - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.source(component.source); - if (!component.fqn.empty()) { - ext.ros2_node(component.fqn); - } - if (!component.namespace_path.empty()) { - ext.ros2_namespace(component.namespace_path); - } - item["x-medkit"] = ext.build(); - - items.push_back(item); - } - - json response; - response["items"] = items; - - // x-medkit for response-level metadata - XMedkit resp_ext; - resp_ext.add("total_count", items.size()); - response["x-medkit"] = resp_ext.build(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error"); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_list_components: %s", e.what()); - } -} - -void ComponentHandlers::handle_get_component(const httplib::Request & req, httplib::Response & res) { - try { - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string component_id = req.matches[1]; - - auto validation_result = ctx_.validate_entity_id(component_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid component ID", - {{"details", validation_result.error()}, {"component_id", component_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto comp_opt = discovery->get_component(component_id); - - if (!comp_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Component not found", - {{"component_id", component_id}}); - return; - } - - const auto & comp = *comp_opt; - - json response; - // Required fields - response["id"] = comp.id; - response["name"] = comp.name.empty() ? comp.id : comp.name; - - // Optional fields - if (!comp.description.empty()) { - response["description"] = comp.description; - } - if (!comp.tags.empty()) { - response["tags"] = comp.tags; - } - - // Capability URIs (flat at top level) - std::string base = "/api/v1/components/" + comp.id; - response["data"] = base + "/data"; - response["operations"] = base + "/operations"; - response["configurations"] = base + "/configurations"; - response["faults"] = base + "/faults"; - response["subcomponents"] = base + "/subcomponents"; - response["hosts"] = base + "/hosts"; // SOVD 7.6.2.4 - - // Add depends-on only when component has dependencies - if (!comp.depends_on.empty()) { - response["depends-on"] = base + "/depends-on"; - } - - // Add belongs-to field referencing the parent Area (SOVD 7.6.3) - if (!comp.area.empty()) { - response["belongs-to"] = "/api/v1/areas/" + comp.area; - } - - // Build HATEOAS links - LinksBuilder links; - links.self(base).collection("/api/v1/components"); - if (!comp.area.empty()) { - links.add("area", "/api/v1/areas/" + comp.area); - } - if (!comp.parent_component_id.empty()) { - links.parent("/api/v1/components/" + comp.parent_component_id); - } - response["_links"] = links.build(); - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.source(comp.source); - if (!comp.fqn.empty()) { - ext.ros2_node(comp.fqn); - } - if (!comp.namespace_path.empty()) { - ext.ros2_namespace(comp.namespace_path); - } - if (!comp.type.empty()) { - ext.add("type", comp.type); - } - - // Add detailed capabilities object to x-medkit - using Cap = CapabilityBuilder::Capability; - std::vector caps = {Cap::DATA, Cap::OPERATIONS, Cap::CONFIGURATIONS, - Cap::FAULTS, Cap::SUBCOMPONENTS, Cap::HOSTS}; - if (!comp.depends_on.empty()) { - caps.push_back(Cap::DEPENDS_ON); - } - ext.add("capabilities", CapabilityBuilder::build_capabilities("components", comp.id, caps)); - response["x-medkit"] = ext.build(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_component: %s", e.what()); - } -} - -void ComponentHandlers::handle_component_data(const httplib::Request & req, httplib::Response & res) { - std::string component_id; - try { - // Extract component_id from URL path - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - component_id = req.matches[1]; - - // Validate component_id - auto validation_result = ctx_.validate_entity_id(component_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid component ID", - {{"details", validation_result.error()}, {"component_id", component_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto comp_opt = discovery->get_component(component_id); - - if (!comp_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Component not found", - {{"component_id", component_id}}); - return; - } - - const auto & component = *comp_opt; - - // Collect all topics - from component directly OR aggregated from related Apps - // Track publisher vs subscriber for direction info - std::set publish_topics; - std::set subscribe_topics; - - // First, check component's own topics - for (const auto & topic : component.topics.publishes) { - publish_topics.insert(topic); - } - for (const auto & topic : component.topics.subscribes) { - subscribe_topics.insert(topic); - } - - // If component has no direct topics (synthetic component), aggregate from Apps - if (publish_topics.empty() && subscribe_topics.empty()) { - auto apps = discovery->get_apps_for_component(component_id); - for (const auto & app : apps) { - for (const auto & topic : app.topics.publishes) { - publish_topics.insert(topic); - } - for (const auto & topic : app.topics.subscribes) { - subscribe_topics.insert(topic); - } - } - } - - // Build items array with ValueMetadata format - json items = json::array(); - - // Add publisher topics - for (const auto & topic_name : publish_topics) { - json item; - // SOVD required fields - item["id"] = normalize_topic_to_id(topic_name); - item["name"] = topic_name; - item["category"] = "currentData"; - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.ros2_topic(topic_name).add_ros2("direction", "publish"); - item["x-medkit"] = ext.build(); - - items.push_back(item); - } - - // Add subscriber topics (avoid duplicates) - for (const auto & topic_name : subscribe_topics) { - // Skip if already added as publisher - if (publish_topics.count(topic_name) > 0) { - continue; - } - - json item; - // SOVD required fields - item["id"] = normalize_topic_to_id(topic_name); - item["name"] = topic_name; - item["category"] = "currentData"; - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.ros2_topic(topic_name).add_ros2("direction", "subscribe"); - item["x-medkit"] = ext.build(); - - items.push_back(item); - } - - // Build response with x-medkit for total_count - json response; - response["items"] = items; - - XMedkit resp_ext; - resp_ext.entity_id(component_id).add("total_count", items.size()); - response["x-medkit"] = resp_ext.build(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, - "Failed to retrieve component data", - {{"details", e.what()}, {"component_id", component_id}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_component_data for component '%s': %s", - component_id.c_str(), e.what()); - } -} - -void ComponentHandlers::handle_component_topic_data(const httplib::Request & req, httplib::Response & res) { - std::string component_id; - std::string topic_name; - try { - // Extract component_id and topic_name from URL path - if (req.matches.size() < 3) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - component_id = req.matches[1]; - // cpp-httplib automatically decodes percent-encoded characters in URL path - // e.g., "powertrain%2Fengine%2Ftemperature" -> "powertrain/engine/temperature" - topic_name = req.matches[2]; - - // Validate component_id - auto component_validation = ctx_.validate_entity_id(component_id); - if (!component_validation) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid component ID", - {{"details", component_validation.error()}, {"component_id", component_id}}); - return; - } - - // Skip topic_name validation - it may contain slashes after URL decoding - // The actual validation happens when we try to find the topic in the ROS graph - - auto discovery = ctx_.node()->get_discovery_manager(); - auto comp_opt = discovery->get_component(component_id); - - if (!comp_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Component not found", - {{"component_id", component_id}}); - return; - } - - // cpp-httplib has already decoded %2F to / in topic_name - // Determine the full ROS topic path - std::string full_topic_path; - if (topic_name.empty() || topic_name[0] == '/') { - full_topic_path = topic_name; - } else { - full_topic_path = "/" + topic_name; - } - - // Also support normalized data IDs (sensor_temperature -> /sensor/temperature search) - // Try both the normalized ID and the raw topic name - - // Get topic data from DataAccessManager - auto data_access_mgr = ctx_.node()->get_data_access_manager(); - auto native_sampler = data_access_mgr->get_native_sampler(); - auto sample = native_sampler->sample_topic(full_topic_path, data_access_mgr->get_topic_sample_timeout()); - - // Build SOVD ReadValue response - json response; - // SOVD required fields - response["id"] = normalize_topic_to_id(full_topic_path); - - // SOVD "data" field contains the actual value - if (sample.has_data && sample.data) { - response["data"] = *sample.data; - } else { - response["data"] = json::object(); // Empty object if no data available - } - - // Build x-medkit extension with ROS2-specific data - XMedkit ext; - ext.ros2_topic(full_topic_path).entity_id(component_id); - if (!sample.message_type.empty()) { - ext.ros2_type(sample.message_type); - } - ext.add("timestamp", sample.timestamp_ns); - ext.add("publisher_count", sample.publisher_count); - ext.add("subscriber_count", sample.subscriber_count); - ext.add("status", sample.has_data ? "data" : "metadata_only"); - response["x-medkit"] = ext.build(); - - HandlerContext::send_json(res, response); - } catch (const TopicNotAvailableException & e) { - // Topic doesn't exist or metadata retrieval failed - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_X_MEDKIT_ROS2_TOPIC_UNAVAILABLE, "Topic not found", - {{"component_id", component_id}, {"topic_name", topic_name}}); - RCLCPP_ERROR(HandlerContext::logger(), "Topic not available for component '%s', topic '%s': %s", - component_id.c_str(), topic_name.c_str(), e.what()); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, - "Failed to retrieve topic data", - {{"details", e.what()}, {"component_id", component_id}, {"topic_name", topic_name}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_component_topic_data for component '%s', topic '%s': %s", - component_id.c_str(), topic_name.c_str(), e.what()); - } -} - -void ComponentHandlers::handle_component_topic_publish(const httplib::Request & req, httplib::Response & res) { - std::string component_id; - std::string topic_name; - try { - // Extract component_id and topic_name from URL path - if (req.matches.size() < 3) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - component_id = req.matches[1]; - // cpp-httplib automatically decodes percent-encoded characters in URL path - // e.g., "chassis%2Fbrakes%2Fcommand" -> "chassis/brakes/command" - topic_name = req.matches[2]; - - // Validate component_id - auto component_validation = ctx_.validate_entity_id(component_id); - if (!component_validation) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid component ID", - {{"details", component_validation.error()}, {"component_id", component_id}}); - return; - } - - // Skip topic_name validation - it may contain slashes after URL decoding - // The actual validation happens when we try to publish to the topic - - // Parse request body - json body; - try { - body = json::parse(req.body); - } catch (const json::parse_error & e) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid JSON in request body", - {{"details", e.what()}}); - return; - } - - // Validate required fields: type and data - if (!body.contains("type") || !body["type"].is_string()) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, - "Missing or invalid 'type' field", - {{"details", "Request body must contain 'type' string field"}}); - return; - } - - if (!body.contains("data")) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Missing 'data' field", - {{"details", "Request body must contain 'data' field"}}); - return; - } - - std::string msg_type = body["type"].get(); - json data = body["data"]; - - // Validate message type format (e.g., std_msgs/msg/Float32) - // Expected format: package/msg/Type (exactly 2 slashes) - size_t slash_count = std::count(msg_type.begin(), msg_type.end(), '/'); - size_t msg_pos = msg_type.find("/msg/"); - bool valid_format = (slash_count == 2) && (msg_pos != std::string::npos) && - (msg_pos > 0) && // package before /msg/ - (msg_pos + 5 < msg_type.length()); // Type after /msg/ - - if (!valid_format) { - HandlerContext::send_error( - res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid message type format", - {{"details", "Message type should be in format: package/msg/Type"}, {"type", msg_type}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto comp_opt = discovery->get_component(component_id); - - if (!comp_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Component not found", - {{"component_id", component_id}}); - return; - } - - // cpp-httplib has already decoded %2F to / in topic_name - // Now just add leading slash to make it a full ROS topic path - // e.g., "chassis/brakes/command" -> "/chassis/brakes/command" - std::string full_topic_path = "/" + topic_name; - - // Publish data using DataAccessManager - auto data_access_mgr = ctx_.node()->get_data_access_manager(); - json result = data_access_mgr->publish_to_topic(full_topic_path, msg_type, data); - - // Build response with x-medkit extension - json response; - // Required fields - response["id"] = normalize_topic_to_id(full_topic_path); - response["data"] = data; // Echo back the written data - - // Build x-medkit extension with ROS2-specific data - XMedkit ext; - ext.ros2_topic(full_topic_path).ros2_type(msg_type).entity_id(component_id); - if (result.contains("status")) { - ext.add("status", result["status"]); - } - if (result.contains("publisher_created")) { - ext.add("publisher_created", result["publisher_created"]); - } - response["x-medkit"] = ext.build(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, - "Failed to publish to topic", - {{"details", e.what()}, {"component_id", component_id}, {"topic_name", topic_name}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_component_topic_publish for component '%s', topic '%s': %s", - component_id.c_str(), topic_name.c_str(), e.what()); - } -} - -void ComponentHandlers::handle_get_subcomponents(const httplib::Request & req, httplib::Response & res) { - try { - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string component_id = req.matches[1]; - - auto validation_result = ctx_.validate_entity_id(component_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid component ID", - {{"details", validation_result.error()}, {"component_id", component_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto comp_opt = discovery->get_component(component_id); - - if (!comp_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Component not found", - {{"component_id", component_id}}); - return; - } - - // Get subcomponents - auto subcomponents = discovery->get_subcomponents(component_id); - - json items = json::array(); - for (const auto & sub : subcomponents) { - json item; - item["id"] = sub.id; - item["name"] = sub.name.empty() ? sub.id : sub.name; - item["href"] = "/api/v1/components/" + sub.id; - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.source(sub.source); - if (!sub.namespace_path.empty()) { - ext.ros2_namespace(sub.namespace_path); - } - item["x-medkit"] = ext.build(); - - items.push_back(item); - } - - json response; - response["items"] = items; - - // x-medkit for response-level metadata - XMedkit resp_ext; - resp_ext.add("total_count", items.size()); - response["x-medkit"] = resp_ext.build(); - - // HATEOAS links - json links; - links["self"] = "/api/v1/components/" + component_id + "/subcomponents"; - links["parent"] = "/api/v1/components/" + component_id; - response["_links"] = links; - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_subcomponents: %s", e.what()); - } -} - -void ComponentHandlers::handle_get_hosts(const httplib::Request & req, httplib::Response & res) { - // @verifies REQ_INTEROP_007 - try { - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string component_id = req.matches[1]; - - auto validation_result = ctx_.validate_entity_id(component_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid component ID", - {{"details", validation_result.error()}, {"component_id", component_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto comp_opt = discovery->get_component(component_id); - - if (!comp_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Component not found", - {{"component_id", component_id}}); - return; - } - - // Get apps hosted on this component (SOVD 7.6.2.4 - non-deprecated relationship) - auto apps = discovery->get_apps_for_component(component_id); - - json items = json::array(); - for (const auto & app : apps) { - json item; - item["id"] = app.id; - item["name"] = app.name.empty() ? app.id : app.name; - item["href"] = "/api/v1/apps/" + app.id; - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.is_online(app.is_online).source(app.source); - if (app.bound_fqn) { - ext.ros2_node(*app.bound_fqn); - } - item["x-medkit"] = ext.build(); - - items.push_back(item); - } - - json response; - response["items"] = items; - - // x-medkit for response-level metadata - XMedkit resp_ext; - resp_ext.add("total_count", items.size()); - response["x-medkit"] = resp_ext.build(); - - // HATEOAS links - json links; - links["self"] = "/api/v1/components/" + component_id + "/hosts"; - links["component"] = "/api/v1/components/" + component_id; - response["_links"] = links; - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_hosts: %s", e.what()); - } -} - -void ComponentHandlers::handle_get_depends_on(const httplib::Request & req, httplib::Response & res) { - try { - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string component_id = req.matches[1]; - - auto validation_result = ctx_.validate_entity_id(component_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid component ID", - {{"details", validation_result.error()}, {"component_id", component_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto comp_opt = discovery->get_component(component_id); - - if (!comp_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Component not found", - {{"component_id", component_id}}); - return; - } - - const auto & comp = *comp_opt; - - // Build list of dependency references - json items = json::array(); - for (const auto & dep_id : comp.depends_on) { - json item; - item["id"] = dep_id; - item["href"] = "/api/v1/components/" + dep_id; - - // Try to get the dependency component for additional info - auto dep_opt = discovery->get_component(dep_id); - if (dep_opt) { - item["name"] = dep_opt->name.empty() ? dep_id : dep_opt->name; - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.source(dep_opt->source); - item["x-medkit"] = ext.build(); - } else { - // Dependency component could not be resolved; mark as missing in x-medkit - item["name"] = dep_id; - XMedkit ext; - ext.add("missing", true); - item["x-medkit"] = ext.build(); - RCLCPP_WARN(HandlerContext::logger(), "Component '%s' declares dependency on unknown component '%s'", - component_id.c_str(), dep_id.c_str()); - } - - items.push_back(item); - } - - json response; - response["items"] = items; - - // x-medkit for response-level metadata - XMedkit resp_ext; - resp_ext.add("total_count", items.size()); - response["x-medkit"] = resp_ext.build(); - - // HATEOAS links - json links; - links["self"] = "/api/v1/components/" + component_id + "/depends-on"; - links["component"] = "/api/v1/components/" + component_id; - response["_links"] = links; - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_depends_on: %s", e.what()); - } -} - -} // namespace handlers -} // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/src/http/handlers/discovery/function_handlers.cpp b/src/ros2_medkit_gateway/src/http/handlers/discovery/function_handlers.cpp deleted file mode 100644 index 54f2ff3..0000000 --- a/src/ros2_medkit_gateway/src/http/handlers/discovery/function_handlers.cpp +++ /dev/null @@ -1,354 +0,0 @@ -// Copyright 2026 bburda -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "ros2_medkit_gateway/http/handlers/discovery/function_handlers.hpp" - -#include "ros2_medkit_gateway/gateway_node.hpp" -#include "ros2_medkit_gateway/http/error_codes.hpp" -#include "ros2_medkit_gateway/http/handlers/capability_builder.hpp" -#include "ros2_medkit_gateway/http/x_medkit.hpp" - -using json = nlohmann::json; -using httplib::StatusCode; - -namespace ros2_medkit_gateway { -namespace handlers { - -void FunctionHandlers::handle_list_functions(const httplib::Request & req, httplib::Response & res) { - (void)req; // Unused parameter - - try { - auto discovery = ctx_.node()->get_discovery_manager(); - auto functions = discovery->discover_functions(); - - // Build items array with EntityReference format - json items = json::array(); - for (const auto & func : functions) { - json func_item; - // SOVD required fields for EntityReference - func_item["id"] = func.id; - func_item["name"] = func.name.empty() ? func.id : func.name; - func_item["href"] = "/api/v1/functions/" + func.id; - - // Optional SOVD fields - if (!func.description.empty()) { - func_item["description"] = func.description; - } - if (!func.tags.empty()) { - func_item["tags"] = func.tags; - } - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.source(func.source); - func_item["x-medkit"] = ext.build(); - - items.push_back(func_item); - } - - json response; - response["items"] = items; - - // x-medkit for response-level metadata - XMedkit resp_ext; - resp_ext.add("total_count", functions.size()); - response["x-medkit"] = resp_ext.build(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_list_functions: %s", e.what()); - } -} - -void FunctionHandlers::handle_get_function(const httplib::Request & req, httplib::Response & res) { - try { - // Extract function_id from URL path - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string function_id = req.matches[1]; - - // Validate function_id - auto validation_result = ctx_.validate_entity_id(function_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid function ID", - {{"details", validation_result.error()}, {"function_id", function_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto func_opt = discovery->get_function(function_id); - - if (!func_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Function not found", - {{"function_id", function_id}}); - return; - } - - const auto & func = *func_opt; - - // Build response - json response; - response["id"] = func.id; - response["name"] = func.name.empty() ? func.id : func.name; - - if (!func.description.empty()) { - response["description"] = func.description; - } - if (!func.translation_id.empty()) { - response["translation_id"] = func.translation_id; - } - if (!func.tags.empty()) { - response["tags"] = func.tags; - } - - // Capability URIs as flat fields at top level - std::string base_uri = "/api/v1/functions/" + func.id; - response["hosts"] = base_uri + "/hosts"; - response["data"] = base_uri + "/data"; - response["operations"] = base_uri + "/operations"; - - // Build capabilities using CapabilityBuilder - using Cap = CapabilityBuilder::Capability; - std::vector caps = {Cap::HOSTS, Cap::DATA, Cap::OPERATIONS}; - response["capabilities"] = CapabilityBuilder::build_capabilities("functions", func.id, caps); - - // Build HATEOAS links using LinksBuilder - LinksBuilder links; - links.self("/api/v1/functions/" + func.id).collection("/api/v1/functions"); - response["_links"] = links.build(); - - // Add depends-on as array if present (special case - multiple links) - if (!func.depends_on.empty()) { - json depends_links = json::array(); - for (const auto & dep_id : func.depends_on) { - depends_links.push_back("/api/v1/functions/" + dep_id); - } - response["_links"]["depends-on"] = depends_links; - } - - // x-medkit extension for ROS2-specific data - XMedkit ext; - ext.source(func.source); - response["x-medkit"] = ext.build(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_function: %s", e.what()); - } -} - -void FunctionHandlers::handle_function_hosts(const httplib::Request & req, httplib::Response & res) { - try { - // Extract function_id from URL path - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string function_id = req.matches[1]; - - // Validate function_id - auto validation_result = ctx_.validate_entity_id(function_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid function ID", - {{"details", validation_result.error()}, {"function_id", function_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto func_opt = discovery->get_function(function_id); - - if (!func_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Function not found", - {{"function_id", function_id}}); - return; - } - - // Get host app IDs - auto host_ids = discovery->get_hosts_for_function(function_id); - - json items = json::array(); - for (const auto & app_id : host_ids) { - auto app_opt = discovery->get_app(app_id); - if (app_opt) { - json item; - item["id"] = app_opt->id; - item["name"] = app_opt->name; - item["href"] = "/api/v1/apps/" + app_opt->id; - if (app_opt->is_online) { - item["is_online"] = true; - } - items.push_back(item); - } - } - - json response; - response["items"] = items; - response["total_count"] = items.size(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_function_hosts: %s", e.what()); - } -} - -void FunctionHandlers::handle_get_function_data(const httplib::Request & req, httplib::Response & res) { - try { - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string function_id = req.matches[1]; - - auto validation_result = ctx_.validate_entity_id(function_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid function ID", - {{"details", validation_result.error()}, {"function_id", function_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto func_opt = discovery->get_function(function_id); - - if (!func_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Function not found", - {{"function_id", function_id}}); - return; - } - - // Aggregate data from all host apps - auto host_ids = discovery->get_hosts_for_function(function_id); - - json items = json::array(); - for (const auto & app_id : host_ids) { - auto app_opt = discovery->get_app(app_id); - if (app_opt) { - // Publishers - for (const auto & topic_name : app_opt->topics.publishes) { - json item; - item["id"] = topic_name; - item["name"] = topic_name; - item["direction"] = "publish"; - item["source_app"] = app_id; - std::string href = "/api/v1/apps/"; - href.append(app_id).append("/data/").append(topic_name); - item["href"] = href; - items.push_back(item); - } - // Subscribers - for (const auto & topic_name : app_opt->topics.subscribes) { - json item; - item["id"] = topic_name; - item["name"] = topic_name; - item["direction"] = "subscribe"; - item["source_app"] = app_id; - std::string href = "/api/v1/apps/"; - href.append(app_id).append("/data/").append(topic_name); - item["href"] = href; - items.push_back(item); - } - } - } - - json response; - response["items"] = items; - response["total_count"] = items.size(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_function_data: %s", e.what()); - } -} - -void FunctionHandlers::handle_list_function_operations(const httplib::Request & req, httplib::Response & res) { - try { - if (req.matches.size() < 2) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); - return; - } - - std::string function_id = req.matches[1]; - - auto validation_result = ctx_.validate_entity_id(function_id); - if (!validation_result) { - HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid function ID", - {{"details", validation_result.error()}, {"function_id", function_id}}); - return; - } - - auto discovery = ctx_.node()->get_discovery_manager(); - auto func_opt = discovery->get_function(function_id); - - if (!func_opt) { - HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Function not found", - {{"function_id", function_id}}); - return; - } - - // Aggregate operations from all host apps - auto host_ids = discovery->get_hosts_for_function(function_id); - - json items = json::array(); - for (const auto & app_id : host_ids) { - auto app_opt = discovery->get_app(app_id); - if (app_opt) { - // Services - for (const auto & svc : app_opt->services) { - json item; - item["id"] = svc.name; - item["name"] = svc.name; - item["type"] = "service"; - item["service_type"] = svc.type; - item["source_app"] = app_id; - items.push_back(item); - } - // Actions - for (const auto & act : app_opt->actions) { - json item; - item["id"] = act.name; - item["name"] = act.name; - item["type"] = "action"; - item["action_type"] = act.type; - item["source_app"] = app_id; - items.push_back(item); - } - } - } - - json response; - response["items"] = items; - response["total_count"] = items.size(); - - HandlerContext::send_json(res, response); - } catch (const std::exception & e) { - HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", - {{"details", e.what()}}); - RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_list_function_operations: %s", e.what()); - } -} - -} // namespace handlers -} // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/src/http/handlers/discovery_handlers.cpp b/src/ros2_medkit_gateway/src/http/handlers/discovery_handlers.cpp new file mode 100644 index 0000000..427d7d4 --- /dev/null +++ b/src/ros2_medkit_gateway/src/http/handlers/discovery_handlers.cpp @@ -0,0 +1,1099 @@ +// Copyright 2026 bburda +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "ros2_medkit_gateway/http/handlers/discovery_handlers.hpp" + +#include +#include + +#include "ros2_medkit_gateway/gateway_node.hpp" +#include "ros2_medkit_gateway/http/error_codes.hpp" +#include "ros2_medkit_gateway/http/handlers/capability_builder.hpp" +#include "ros2_medkit_gateway/http/http_utils.hpp" +#include "ros2_medkit_gateway/http/x_medkit.hpp" + +using json = nlohmann::json; +using httplib::StatusCode; + +namespace ros2_medkit_gateway { +namespace handlers { + +// ============================================================================= +// Area handlers +// ============================================================================= + +void DiscoveryHandlers::handle_list_areas(const httplib::Request & req, httplib::Response & res) { + (void)req; + + try { + const auto & cache = ctx_.node()->get_thread_safe_cache(); + const auto areas = cache.get_areas(); + + json items = json::array(); + for (const auto & area : areas) { + json area_item; + area_item["id"] = area.id; + area_item["name"] = area.name.empty() ? area.id : area.name; + area_item["href"] = "/api/v1/areas/" + area.id; + + if (!area.description.empty()) { + area_item["description"] = area.description; + } + if (!area.tags.empty()) { + area_item["tags"] = area.tags; + } + + XMedkit ext; + ext.ros2_namespace(area.namespace_path); + if (!area.parent_area_id.empty()) { + ext.add("parent_area_id", area.parent_area_id); + } + area_item["x-medkit"] = ext.build(); + + items.push_back(area_item); + } + + json response; + response["items"] = items; + + XMedkit resp_ext; + resp_ext.add("total_count", items.size()); + response["x-medkit"] = resp_ext.build(); + + HandlerContext::send_json(res, response); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error"); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_list_areas: %s", e.what()); + } +} + +void DiscoveryHandlers::handle_get_area(const httplib::Request & req, httplib::Response & res) { + try { + if (req.matches.size() < 2) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); + return; + } + + std::string area_id = req.matches[1]; + + auto validation_result = ctx_.validate_entity_id(area_id); + if (!validation_result) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid area ID", + {{"details", validation_result.error()}, {"area_id", area_id}}); + return; + } + + auto discovery = ctx_.node()->get_discovery_manager(); + auto area_opt = discovery->get_area(area_id); + + if (!area_opt) { + HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Area not found", + {{"area_id", area_id}}); + return; + } + + const auto & area = *area_opt; + + json response; + response["id"] = area.id; + response["name"] = area.name.empty() ? area.id : area.name; + + if (!area.description.empty()) { + response["description"] = area.description; + } + if (!area.tags.empty()) { + response["tags"] = area.tags; + } + + std::string base_uri = "/api/v1/areas/" + area.id; + response["subareas"] = base_uri + "/subareas"; + response["components"] = base_uri + "/components"; + response["contains"] = base_uri + "/contains"; + response["data"] = base_uri + "/data"; + response["operations"] = base_uri + "/operations"; + response["configurations"] = base_uri + "/configurations"; + response["faults"] = base_uri + "/faults"; + + using Cap = CapabilityBuilder::Capability; + std::vector caps = {Cap::SUBAREAS, Cap::CONTAINS, Cap::DATA, + Cap::OPERATIONS, Cap::CONFIGURATIONS, Cap::FAULTS}; + response["capabilities"] = CapabilityBuilder::build_capabilities("areas", area.id, caps); + + LinksBuilder links; + links.self("/api/v1/areas/" + area.id).collection("/api/v1/areas"); + if (!area.parent_area_id.empty()) { + links.parent("/api/v1/areas/" + area.parent_area_id); + } + response["_links"] = links.build(); + + XMedkit ext; + ext.ros2_namespace(area.namespace_path); + if (!area.parent_area_id.empty()) { + ext.add("parent_area_id", area.parent_area_id); + } + response["x-medkit"] = ext.build(); + + HandlerContext::send_json(res, response); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", + {{"details", e.what()}}); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_area: %s", e.what()); + } +} + +void DiscoveryHandlers::handle_area_components(const httplib::Request & req, httplib::Response & res) { + try { + if (req.matches.size() < 2) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); + return; + } + + std::string area_id = req.matches[1]; + + auto validation_result = ctx_.validate_entity_id(area_id); + if (!validation_result) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid area ID", + {{"details", validation_result.error()}, {"area_id", area_id}}); + return; + } + + const auto & cache = ctx_.node()->get_thread_safe_cache(); + + if (!cache.has_area(area_id)) { + HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Area not found", + {{"area_id", area_id}}); + return; + } + + const auto components = cache.get_components(); + json items = json::array(); + for (const auto & component : components) { + if (component.area == area_id) { + json comp_item; + comp_item["id"] = component.id; + comp_item["name"] = component.name.empty() ? component.id : component.name; + comp_item["href"] = "/api/v1/components/" + component.id; + + if (!component.description.empty()) { + comp_item["description"] = component.description; + } + + XMedkit ext; + ext.source(component.source); + if (!component.namespace_path.empty()) { + ext.ros2_namespace(component.namespace_path); + } + comp_item["x-medkit"] = ext.build(); + + items.push_back(comp_item); + } + } + + json response; + response["items"] = items; + + XMedkit resp_ext; + resp_ext.add("total_count", items.size()); + response["x-medkit"] = resp_ext.build(); + + HandlerContext::send_json(res, response); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error"); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_area_components: %s", e.what()); + } +} + +void DiscoveryHandlers::handle_get_subareas(const httplib::Request & req, httplib::Response & res) { + try { + if (req.matches.size() < 2) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); + return; + } + + std::string area_id = req.matches[1]; + + auto validation_result = ctx_.validate_entity_id(area_id); + if (!validation_result) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid area ID", + {{"details", validation_result.error()}, {"area_id", area_id}}); + return; + } + + auto discovery = ctx_.node()->get_discovery_manager(); + auto area_opt = discovery->get_area(area_id); + + if (!area_opt) { + HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Area not found", + {{"area_id", area_id}}); + return; + } + + auto subareas = discovery->get_subareas(area_id); + + json items = json::array(); + for (const auto & subarea : subareas) { + json item; + item["id"] = subarea.id; + item["name"] = subarea.name.empty() ? subarea.id : subarea.name; + item["href"] = "/api/v1/areas/" + subarea.id; + + XMedkit ext; + ext.ros2_namespace(subarea.namespace_path); + item["x-medkit"] = ext.build(); + + items.push_back(item); + } + + json response; + response["items"] = items; + + XMedkit resp_ext; + resp_ext.add("total_count", items.size()); + response["x-medkit"] = resp_ext.build(); + + json links; + links["self"] = "/api/v1/areas/" + area_id + "/subareas"; + links["parent"] = "/api/v1/areas/" + area_id; + response["_links"] = links; + + HandlerContext::send_json(res, response); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", + {{"details", e.what()}}); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_subareas: %s", e.what()); + } +} + +void DiscoveryHandlers::handle_get_contains(const httplib::Request & req, httplib::Response & res) { + // @verifies REQ_INTEROP_006 + try { + if (req.matches.size() < 2) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); + return; + } + + std::string area_id = req.matches[1]; + + auto validation_result = ctx_.validate_entity_id(area_id); + if (!validation_result) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid area ID", + {{"details", validation_result.error()}, {"area_id", area_id}}); + return; + } + + auto discovery = ctx_.node()->get_discovery_manager(); + auto area_opt = discovery->get_area(area_id); + + if (!area_opt) { + HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Area not found", + {{"area_id", area_id}}); + return; + } + + auto components = discovery->get_components_for_area(area_id); + + json items = json::array(); + for (const auto & comp : components) { + json item; + item["id"] = comp.id; + item["name"] = comp.name.empty() ? comp.id : comp.name; + item["href"] = "/api/v1/components/" + comp.id; + + XMedkit ext; + ext.source(comp.source); + if (!comp.namespace_path.empty()) { + ext.ros2_namespace(comp.namespace_path); + } + item["x-medkit"] = ext.build(); + + items.push_back(item); + } + + json response; + response["items"] = items; + + XMedkit resp_ext; + resp_ext.add("total_count", items.size()); + response["x-medkit"] = resp_ext.build(); + + json links; + links["self"] = "/api/v1/areas/" + area_id + "/contains"; + links["area"] = "/api/v1/areas/" + area_id; + response["_links"] = links; + + HandlerContext::send_json(res, response); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", + {{"details", e.what()}}); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_contains: %s", e.what()); + } +} + +// ============================================================================= +// Component handlers +// ============================================================================= + +void DiscoveryHandlers::handle_list_components(const httplib::Request & req, httplib::Response & res) { + (void)req; + + try { + const auto & cache = ctx_.node()->get_thread_safe_cache(); + const auto components = cache.get_components(); + + json items = json::array(); + for (const auto & component : components) { + json item; + item["id"] = component.id; + item["name"] = component.name.empty() ? component.id : component.name; + item["href"] = "/api/v1/components/" + component.id; + + if (!component.description.empty()) { + item["description"] = component.description; + } + if (!component.tags.empty()) { + item["tags"] = component.tags; + } + + XMedkit ext; + ext.source(component.source); + if (!component.fqn.empty()) { + ext.ros2_node(component.fqn); + } + if (!component.namespace_path.empty()) { + ext.ros2_namespace(component.namespace_path); + } + item["x-medkit"] = ext.build(); + + items.push_back(item); + } + + json response; + response["items"] = items; + + XMedkit resp_ext; + resp_ext.add("total_count", items.size()); + response["x-medkit"] = resp_ext.build(); + + HandlerContext::send_json(res, response); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error"); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_list_components: %s", e.what()); + } +} + +void DiscoveryHandlers::handle_get_component(const httplib::Request & req, httplib::Response & res) { + try { + if (req.matches.size() < 2) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); + return; + } + + std::string component_id = req.matches[1]; + + auto validation_result = ctx_.validate_entity_id(component_id); + if (!validation_result) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid component ID", + {{"details", validation_result.error()}, {"component_id", component_id}}); + return; + } + + auto discovery = ctx_.node()->get_discovery_manager(); + auto comp_opt = discovery->get_component(component_id); + + if (!comp_opt) { + HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Component not found", + {{"component_id", component_id}}); + return; + } + + const auto & comp = *comp_opt; + + json response; + response["id"] = comp.id; + response["name"] = comp.name.empty() ? comp.id : comp.name; + + if (!comp.description.empty()) { + response["description"] = comp.description; + } + if (!comp.tags.empty()) { + response["tags"] = comp.tags; + } + + std::string base = "/api/v1/components/" + comp.id; + response["data"] = base + "/data"; + response["operations"] = base + "/operations"; + response["configurations"] = base + "/configurations"; + response["faults"] = base + "/faults"; + response["subcomponents"] = base + "/subcomponents"; + response["hosts"] = base + "/hosts"; + + if (!comp.depends_on.empty()) { + response["depends-on"] = base + "/depends-on"; + } + + if (!comp.area.empty()) { + response["belongs-to"] = "/api/v1/areas/" + comp.area; + } + + LinksBuilder links; + links.self(base).collection("/api/v1/components"); + if (!comp.area.empty()) { + links.add("area", "/api/v1/areas/" + comp.area); + } + if (!comp.parent_component_id.empty()) { + links.parent("/api/v1/components/" + comp.parent_component_id); + } + response["_links"] = links.build(); + + XMedkit ext; + ext.source(comp.source); + if (!comp.fqn.empty()) { + ext.ros2_node(comp.fqn); + } + if (!comp.namespace_path.empty()) { + ext.ros2_namespace(comp.namespace_path); + } + if (!comp.type.empty()) { + ext.add("type", comp.type); + } + + using Cap = CapabilityBuilder::Capability; + std::vector caps = {Cap::DATA, Cap::OPERATIONS, Cap::CONFIGURATIONS, + Cap::FAULTS, Cap::SUBCOMPONENTS, Cap::HOSTS}; + if (!comp.depends_on.empty()) { + caps.push_back(Cap::DEPENDS_ON); + } + ext.add("capabilities", CapabilityBuilder::build_capabilities("components", comp.id, caps)); + response["x-medkit"] = ext.build(); + + HandlerContext::send_json(res, response); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", + {{"details", e.what()}}); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_component: %s", e.what()); + } +} + +void DiscoveryHandlers::handle_get_subcomponents(const httplib::Request & req, httplib::Response & res) { + try { + if (req.matches.size() < 2) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); + return; + } + + std::string component_id = req.matches[1]; + + auto validation_result = ctx_.validate_entity_id(component_id); + if (!validation_result) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid component ID", + {{"details", validation_result.error()}, {"component_id", component_id}}); + return; + } + + auto discovery = ctx_.node()->get_discovery_manager(); + auto comp_opt = discovery->get_component(component_id); + + if (!comp_opt) { + HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Component not found", + {{"component_id", component_id}}); + return; + } + + auto subcomponents = discovery->get_subcomponents(component_id); + + json items = json::array(); + for (const auto & sub : subcomponents) { + json item; + item["id"] = sub.id; + item["name"] = sub.name.empty() ? sub.id : sub.name; + item["href"] = "/api/v1/components/" + sub.id; + + XMedkit ext; + ext.source(sub.source); + if (!sub.namespace_path.empty()) { + ext.ros2_namespace(sub.namespace_path); + } + item["x-medkit"] = ext.build(); + + items.push_back(item); + } + + json response; + response["items"] = items; + + XMedkit resp_ext; + resp_ext.add("total_count", items.size()); + response["x-medkit"] = resp_ext.build(); + + json links; + links["self"] = "/api/v1/components/" + component_id + "/subcomponents"; + links["parent"] = "/api/v1/components/" + component_id; + response["_links"] = links; + + HandlerContext::send_json(res, response); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", + {{"details", e.what()}}); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_subcomponents: %s", e.what()); + } +} + +void DiscoveryHandlers::handle_get_hosts(const httplib::Request & req, httplib::Response & res) { + // @verifies REQ_INTEROP_007 + try { + if (req.matches.size() < 2) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); + return; + } + + std::string component_id = req.matches[1]; + + auto validation_result = ctx_.validate_entity_id(component_id); + if (!validation_result) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid component ID", + {{"details", validation_result.error()}, {"component_id", component_id}}); + return; + } + + auto discovery = ctx_.node()->get_discovery_manager(); + auto comp_opt = discovery->get_component(component_id); + + if (!comp_opt) { + HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Component not found", + {{"component_id", component_id}}); + return; + } + + auto apps = discovery->get_apps_for_component(component_id); + + json items = json::array(); + for (const auto & app : apps) { + json item; + item["id"] = app.id; + item["name"] = app.name.empty() ? app.id : app.name; + item["href"] = "/api/v1/apps/" + app.id; + + XMedkit ext; + ext.is_online(app.is_online).source(app.source); + if (app.bound_fqn) { + ext.ros2_node(*app.bound_fqn); + } + item["x-medkit"] = ext.build(); + + items.push_back(item); + } + + json response; + response["items"] = items; + + XMedkit resp_ext; + resp_ext.add("total_count", items.size()); + response["x-medkit"] = resp_ext.build(); + + json links; + links["self"] = "/api/v1/components/" + component_id + "/hosts"; + links["component"] = "/api/v1/components/" + component_id; + response["_links"] = links; + + HandlerContext::send_json(res, response); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", + {{"details", e.what()}}); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_hosts: %s", e.what()); + } +} + +void DiscoveryHandlers::handle_component_depends_on(const httplib::Request & req, httplib::Response & res) { + try { + if (req.matches.size() < 2) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); + return; + } + + std::string component_id = req.matches[1]; + + auto validation_result = ctx_.validate_entity_id(component_id); + if (!validation_result) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid component ID", + {{"details", validation_result.error()}, {"component_id", component_id}}); + return; + } + + auto discovery = ctx_.node()->get_discovery_manager(); + auto comp_opt = discovery->get_component(component_id); + + if (!comp_opt) { + HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Component not found", + {{"component_id", component_id}}); + return; + } + + const auto & comp = *comp_opt; + + json items = json::array(); + for (const auto & dep_id : comp.depends_on) { + json item; + item["id"] = dep_id; + item["href"] = "/api/v1/components/" + dep_id; + + auto dep_opt = discovery->get_component(dep_id); + if (dep_opt) { + item["name"] = dep_opt->name.empty() ? dep_id : dep_opt->name; + + XMedkit ext; + ext.source(dep_opt->source); + item["x-medkit"] = ext.build(); + } else { + item["name"] = dep_id; + XMedkit ext; + ext.add("missing", true); + item["x-medkit"] = ext.build(); + RCLCPP_WARN(HandlerContext::logger(), "Component '%s' declares dependency on unknown component '%s'", + component_id.c_str(), dep_id.c_str()); + } + + items.push_back(item); + } + + json response; + response["items"] = items; + + XMedkit resp_ext; + resp_ext.add("total_count", items.size()); + response["x-medkit"] = resp_ext.build(); + + json links; + links["self"] = "/api/v1/components/" + component_id + "/depends-on"; + links["component"] = "/api/v1/components/" + component_id; + response["_links"] = links; + + HandlerContext::send_json(res, response); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", + {{"details", e.what()}}); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_component_depends_on: %s", e.what()); + } +} + +// ============================================================================= +// App handlers +// ============================================================================= + +void DiscoveryHandlers::handle_list_apps(const httplib::Request & req, httplib::Response & res) { + (void)req; + + try { + // Use ThreadSafeEntityCache for consistent discovery (avoids race with data endpoints) + const auto & cache = ctx_.node()->get_thread_safe_cache(); + auto apps = cache.get_apps(); + + json items = json::array(); + for (const auto & app : apps) { + json app_item; + app_item["id"] = app.id; + app_item["name"] = app.name.empty() ? app.id : app.name; + app_item["href"] = "/api/v1/apps/" + app.id; + + if (!app.description.empty()) { + app_item["description"] = app.description; + } + if (!app.tags.empty()) { + app_item["tags"] = app.tags; + } + + XMedkit ext; + ext.source(app.source).is_online(app.is_online); + if (!app.component_id.empty()) { + ext.component_id(app.component_id); + } + if (app.bound_fqn) { + ext.ros2_node(*app.bound_fqn); + } + app_item["x-medkit"] = ext.build(); + + items.push_back(app_item); + } + + json response; + response["items"] = items; + + XMedkit resp_ext; + resp_ext.add("total_count", items.size()); + response["x-medkit"] = resp_ext.build(); + + HandlerContext::send_json(res, response); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", + {{"details", e.what()}}); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_list_apps: %s", e.what()); + } +} + +void DiscoveryHandlers::handle_get_app(const httplib::Request & req, httplib::Response & res) { + try { + if (req.matches.size() < 2) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); + return; + } + + std::string app_id = req.matches[1]; + + auto validation_result = ctx_.validate_entity_id(app_id); + if (!validation_result) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid app ID", + {{"details", validation_result.error()}, {"app_id", app_id}}); + return; + } + + auto discovery = ctx_.node()->get_discovery_manager(); + auto app_opt = discovery->get_app(app_id); + + if (!app_opt) { + HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "App not found", + {{"app_id", app_id}}); + return; + } + + const auto & app = *app_opt; + + json response; + response["id"] = app.id; + response["name"] = app.name; + + if (!app.description.empty()) { + response["description"] = app.description; + } + if (!app.translation_id.empty()) { + response["translation_id"] = app.translation_id; + } + if (!app.tags.empty()) { + response["tags"] = app.tags; + } + + std::string base_uri = "/api/v1/apps/" + app.id; + response["data"] = base_uri + "/data"; + response["operations"] = base_uri + "/operations"; + response["configurations"] = base_uri + "/configurations"; + response["faults"] = base_uri + "/faults"; + + if (!app.component_id.empty()) { + response["is-located-on"] = "/api/v1/components/" + app.component_id; + } + + if (!app.depends_on.empty()) { + response["depends-on"] = base_uri + "/depends-on"; + } + + using Cap = CapabilityBuilder::Capability; + std::vector caps = {Cap::DATA, Cap::OPERATIONS, Cap::CONFIGURATIONS, Cap::FAULTS}; + response["capabilities"] = CapabilityBuilder::build_capabilities("apps", app.id, caps); + + LinksBuilder links; + links.self("/api/v1/apps/" + app.id).collection("/api/v1/apps"); + if (!app.component_id.empty()) { + links.add("is-located-on", "/api/v1/components/" + app.component_id); + } + response["_links"] = links.build(); + + if (!app.depends_on.empty()) { + json depends_links = json::array(); + for (const auto & dep_id : app.depends_on) { + depends_links.push_back("/api/v1/apps/" + dep_id); + } + response["_links"]["depends-on"] = depends_links; + } + + XMedkit ext; + ext.source(app.source).is_online(app.is_online); + if (app.bound_fqn) { + ext.ros2_node(*app.bound_fqn); + } + if (!app.component_id.empty()) { + ext.component_id(app.component_id); + } + response["x-medkit"] = ext.build(); + + HandlerContext::send_json(res, response); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", + {{"details", e.what()}}); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_app: %s", e.what()); + } +} + +void DiscoveryHandlers::handle_app_depends_on(const httplib::Request & req, httplib::Response & res) { + try { + if (req.matches.size() < 2) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); + return; + } + + std::string app_id = req.matches[1]; + + auto validation_result = ctx_.validate_entity_id(app_id); + if (!validation_result) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid app ID", + {{"details", validation_result.error()}, {"app_id", app_id}}); + return; + } + + auto discovery = ctx_.node()->get_discovery_manager(); + auto app_opt = discovery->get_app(app_id); + + if (!app_opt) { + HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "App not found", + {{"app_id", app_id}}); + return; + } + + const auto & app = *app_opt; + + json items = json::array(); + for (const auto & dep_id : app.depends_on) { + json item; + item["id"] = dep_id; + item["href"] = "/api/v1/apps/" + dep_id; + + auto dep_opt = discovery->get_app(dep_id); + if (dep_opt) { + item["name"] = dep_opt->name.empty() ? dep_id : dep_opt->name; + + XMedkit ext; + ext.source(dep_opt->source).is_online(dep_opt->is_online); + item["x-medkit"] = ext.build(); + } else { + item["name"] = dep_id; + XMedkit ext; + ext.add("missing", true); + item["x-medkit"] = ext.build(); + RCLCPP_WARN(HandlerContext::logger(), "App '%s' declares dependency on unknown app '%s'", app_id.c_str(), + dep_id.c_str()); + } + + items.push_back(item); + } + + json response; + response["items"] = items; + + XMedkit resp_ext; + resp_ext.add("total_count", items.size()); + response["x-medkit"] = resp_ext.build(); + + json links; + links["self"] = "/api/v1/apps/" + app_id + "/depends-on"; + links["app"] = "/api/v1/apps/" + app_id; + response["_links"] = links; + + HandlerContext::send_json(res, response); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", + {{"details", e.what()}}); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_app_depends_on: %s", e.what()); + } +} + +// ============================================================================= +// Function handlers +// ============================================================================= + +void DiscoveryHandlers::handle_list_functions(const httplib::Request & req, httplib::Response & res) { + (void)req; + + try { + // Use ThreadSafeEntityCache for consistent discovery (avoids race with data endpoints) + const auto & cache = ctx_.node()->get_thread_safe_cache(); + auto functions = cache.get_functions(); + + json items = json::array(); + for (const auto & func : functions) { + json func_item; + func_item["id"] = func.id; + func_item["name"] = func.name.empty() ? func.id : func.name; + func_item["href"] = "/api/v1/functions/" + func.id; + + if (!func.description.empty()) { + func_item["description"] = func.description; + } + if (!func.tags.empty()) { + func_item["tags"] = func.tags; + } + + XMedkit ext; + ext.source(func.source); + func_item["x-medkit"] = ext.build(); + + items.push_back(func_item); + } + + json response; + response["items"] = items; + + XMedkit resp_ext; + resp_ext.add("total_count", functions.size()); + response["x-medkit"] = resp_ext.build(); + + HandlerContext::send_json(res, response); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", + {{"details", e.what()}}); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_list_functions: %s", e.what()); + } +} + +void DiscoveryHandlers::handle_get_function(const httplib::Request & req, httplib::Response & res) { + try { + if (req.matches.size() < 2) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); + return; + } + + std::string function_id = req.matches[1]; + + auto validation_result = ctx_.validate_entity_id(function_id); + if (!validation_result) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid function ID", + {{"details", validation_result.error()}, {"function_id", function_id}}); + return; + } + + auto discovery = ctx_.node()->get_discovery_manager(); + auto func_opt = discovery->get_function(function_id); + + if (!func_opt) { + HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Function not found", + {{"function_id", function_id}}); + return; + } + + const auto & func = *func_opt; + + json response; + response["id"] = func.id; + response["name"] = func.name.empty() ? func.id : func.name; + + if (!func.description.empty()) { + response["description"] = func.description; + } + if (!func.translation_id.empty()) { + response["translation_id"] = func.translation_id; + } + if (!func.tags.empty()) { + response["tags"] = func.tags; + } + + std::string base_uri = "/api/v1/functions/" + func.id; + response["hosts"] = base_uri + "/hosts"; + response["data"] = base_uri + "/data"; + response["operations"] = base_uri + "/operations"; + response["configurations"] = base_uri + "/configurations"; + response["faults"] = base_uri + "/faults"; + + using Cap = CapabilityBuilder::Capability; + std::vector caps = {Cap::HOSTS, Cap::DATA, Cap::OPERATIONS, Cap::CONFIGURATIONS, Cap::FAULTS}; + response["capabilities"] = CapabilityBuilder::build_capabilities("functions", func.id, caps); + + LinksBuilder links; + links.self("/api/v1/functions/" + func.id).collection("/api/v1/functions"); + response["_links"] = links.build(); + + if (!func.depends_on.empty()) { + json depends_links = json::array(); + for (const auto & dep_id : func.depends_on) { + depends_links.push_back("/api/v1/functions/" + dep_id); + } + response["_links"]["depends-on"] = depends_links; + } + + XMedkit ext; + ext.source(func.source); + response["x-medkit"] = ext.build(); + + HandlerContext::send_json(res, response); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", + {{"details", e.what()}}); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_get_function: %s", e.what()); + } +} + +void DiscoveryHandlers::handle_function_hosts(const httplib::Request & req, httplib::Response & res) { + try { + if (req.matches.size() < 2) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid request"); + return; + } + + std::string function_id = req.matches[1]; + + auto validation_result = ctx_.validate_entity_id(function_id); + if (!validation_result) { + HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, "Invalid function ID", + {{"details", validation_result.error()}, {"function_id", function_id}}); + return; + } + + auto discovery = ctx_.node()->get_discovery_manager(); + auto func_opt = discovery->get_function(function_id); + + if (!func_opt) { + HandlerContext::send_error(res, StatusCode::NotFound_404, ERR_ENTITY_NOT_FOUND, "Function not found", + {{"function_id", function_id}}); + return; + } + + auto host_ids = discovery->get_hosts_for_function(function_id); + + json items = json::array(); + for (const auto & app_id : host_ids) { + auto app_opt = discovery->get_app(app_id); + if (app_opt) { + json item; + item["id"] = app_opt->id; + item["name"] = app_opt->name.empty() ? app_opt->id : app_opt->name; + item["href"] = "/api/v1/apps/" + app_opt->id; + + XMedkit ext; + ext.is_online(app_opt->is_online).source(app_opt->source); + if (app_opt->bound_fqn) { + ext.ros2_node(*app_opt->bound_fqn); + } + item["x-medkit"] = ext.build(); + + items.push_back(item); + } + } + + json response; + response["items"] = items; + + XMedkit resp_ext; + resp_ext.add("total_count", items.size()); + response["x-medkit"] = resp_ext.build(); + + json links; + links["self"] = "/api/v1/functions/" + function_id + "/hosts"; + links["function"] = "/api/v1/functions/" + function_id; + response["_links"] = links; + + HandlerContext::send_json(res, response); + } catch (const std::exception & e) { + HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Internal server error", + {{"details", e.what()}}); + RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_function_hosts: %s", e.what()); + } +} + +} // namespace handlers +} // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/src/http/rest_server.cpp b/src/ros2_medkit_gateway/src/http/rest_server.cpp index c61e42e..830ed2f 100644 --- a/src/ros2_medkit_gateway/src/http/rest_server.cpp +++ b/src/ros2_medkit_gateway/src/http/rest_server.cpp @@ -53,10 +53,8 @@ RESTServer::RESTServer(GatewayNode * node, const std::string & host, int port, c std::make_unique(node_, cors_config_, auth_config_, tls_config_, auth_manager_.get()); health_handlers_ = std::make_unique(*handler_ctx_); - area_handlers_ = std::make_unique(*handler_ctx_); - component_handlers_ = std::make_unique(*handler_ctx_); - app_handlers_ = std::make_unique(*handler_ctx_); - function_handlers_ = std::make_unique(*handler_ctx_); + discovery_handlers_ = std::make_unique(*handler_ctx_); + data_handlers_ = std::make_unique(*handler_ctx_); operation_handlers_ = std::make_unique(*handler_ctx_); config_handlers_ = std::make_unique(*handler_ctx_); fault_handlers_ = std::make_unique(*handler_ctx_); @@ -199,41 +197,41 @@ void RESTServer::setup_routes() { // Areas srv->Get(api_path("/areas"), [this](const httplib::Request & req, httplib::Response & res) { - area_handlers_->handle_list_areas(req, res); + discovery_handlers_->handle_list_areas(req, res); }); // Apps - must register before /apps/{id} to avoid regex conflict srv->Get(api_path("/apps"), [this](const httplib::Request & req, httplib::Response & res) { - app_handlers_->handle_list_apps(req, res); + discovery_handlers_->handle_list_apps(req, res); }); // App data item (specific topic) - register before /apps/{id}/data srv->Get((api_path("/apps") + R"(/([^/]+)/data/(.+)$)"), [this](const httplib::Request & req, httplib::Response & res) { - app_handlers_->handle_get_app_data_item(req, res); + data_handlers_->handle_get_data_item(req, res); }); // App data write (PUT) - publish data to topic srv->Put((api_path("/apps") + R"(/([^/]+)/data/(.+)$)"), [this](const httplib::Request & req, httplib::Response & res) { - app_handlers_->handle_put_app_data_item(req, res); + data_handlers_->handle_put_data_item(req, res); }); // App data-categories (not implemented for ROS 2) srv->Get((api_path("/apps") + R"(/([^/]+)/data-categories$)"), [this](const httplib::Request & req, httplib::Response & res) { - app_handlers_->handle_data_categories(req, res); + data_handlers_->handle_data_categories(req, res); }); // App data-groups (not implemented for ROS 2) srv->Get((api_path("/apps") + R"(/([^/]+)/data-groups$)"), [this](const httplib::Request & req, httplib::Response & res) { - app_handlers_->handle_data_groups(req, res); + data_handlers_->handle_data_groups(req, res); }); // App data (all topics) srv->Get((api_path("/apps") + R"(/([^/]+)/data$)"), [this](const httplib::Request & req, httplib::Response & res) { - app_handlers_->handle_get_app_data(req, res); + data_handlers_->handle_list_data(req, res); }); // App operations @@ -312,111 +310,313 @@ void RESTServer::setup_routes() { // App depends-on (relationship endpoint) srv->Get((api_path("/apps") + R"(/([^/]+)/depends-on$)"), [this](const httplib::Request & req, httplib::Response & res) { - app_handlers_->handle_get_depends_on(req, res); + discovery_handlers_->handle_app_depends_on(req, res); }); // Single app (capabilities) - must be after more specific routes srv->Get((api_path("/apps") + R"(/([^/]+)$)"), [this](const httplib::Request & req, httplib::Response & res) { - app_handlers_->handle_get_app(req, res); + discovery_handlers_->handle_get_app(req, res); }); // Functions - list all functions srv->Get(api_path("/functions"), [this](const httplib::Request & req, httplib::Response & res) { - function_handlers_->handle_list_functions(req, res); + discovery_handlers_->handle_list_functions(req, res); }); // Function hosts srv->Get((api_path("/functions") + R"(/([^/]+)/hosts$)"), [this](const httplib::Request & req, httplib::Response & res) { - function_handlers_->handle_function_hosts(req, res); + discovery_handlers_->handle_function_hosts(req, res); + }); + + // Function data item (specific topic) - register before /functions/{id}/data + srv->Get((api_path("/functions") + R"(/([^/]+)/data/(.+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + data_handlers_->handle_get_data_item(req, res); + }); + + // Function data write (PUT) - publish data to topic + srv->Put((api_path("/functions") + R"(/([^/]+)/data/(.+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + data_handlers_->handle_put_data_item(req, res); }); // Function data (aggregated from host apps) srv->Get((api_path("/functions") + R"(/([^/]+)/data$)"), [this](const httplib::Request & req, httplib::Response & res) { - function_handlers_->handle_get_function_data(req, res); + data_handlers_->handle_list_data(req, res); }); // Function operations (aggregated from host apps) srv->Get((api_path("/functions") + R"(/([^/]+)/operations$)"), [this](const httplib::Request & req, httplib::Response & res) { - function_handlers_->handle_list_function_operations(req, res); + operation_handlers_->handle_list_operations(req, res); + }); + + // Function operation details (GET) - get single operation info + srv->Get((api_path("/functions") + R"(/([^/]+)/operations/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + operation_handlers_->handle_get_operation(req, res); + }); + + // Execution endpoints for functions + srv->Post((api_path("/functions") + R"(/([^/]+)/operations/([^/]+)/executions$)"), + [this](const httplib::Request & req, httplib::Response & res) { + operation_handlers_->handle_create_execution(req, res); + }); + + srv->Get((api_path("/functions") + R"(/([^/]+)/operations/([^/]+)/executions$)"), + [this](const httplib::Request & req, httplib::Response & res) { + operation_handlers_->handle_list_executions(req, res); + }); + + srv->Get((api_path("/functions") + R"(/([^/]+)/operations/([^/]+)/executions/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + operation_handlers_->handle_get_execution(req, res); + }); + + srv->Put((api_path("/functions") + R"(/([^/]+)/operations/([^/]+)/executions/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + operation_handlers_->handle_update_execution(req, res); + }); + + srv->Delete((api_path("/functions") + R"(/([^/]+)/operations/([^/]+)/executions/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + operation_handlers_->handle_cancel_execution(req, res); + }); + + // Function configurations + srv->Get((api_path("/functions") + R"(/([^/]+)/configurations$)"), + [this](const httplib::Request & req, httplib::Response & res) { + config_handlers_->handle_list_configurations(req, res); + }); + + srv->Get((api_path("/functions") + R"(/([^/]+)/configurations/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + config_handlers_->handle_get_configuration(req, res); + }); + + srv->Put((api_path("/functions") + R"(/([^/]+)/configurations/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + config_handlers_->handle_set_configuration(req, res); + }); + + srv->Delete((api_path("/functions") + R"(/([^/]+)/configurations/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + config_handlers_->handle_delete_configuration(req, res); + }); + + srv->Delete((api_path("/functions") + R"(/([^/]+)/configurations$)"), + [this](const httplib::Request & req, httplib::Response & res) { + config_handlers_->handle_delete_all_configurations(req, res); + }); + + // Function faults + srv->Get((api_path("/functions") + R"(/([^/]+)/faults$)"), + [this](const httplib::Request & req, httplib::Response & res) { + fault_handlers_->handle_list_faults(req, res); + }); + + srv->Get((api_path("/functions") + R"(/([^/]+)/faults/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + fault_handlers_->handle_get_fault(req, res); + }); + + srv->Delete((api_path("/functions") + R"(/([^/]+)/faults/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + fault_handlers_->handle_clear_fault(req, res); + }); + + srv->Delete((api_path("/functions") + R"(/([^/]+)/faults$)"), + [this](const httplib::Request & req, httplib::Response & res) { + fault_handlers_->handle_clear_all_faults(req, res); + }); + + srv->Get((api_path("/functions") + R"(/([^/]+)/faults/([^/]+)/snapshots$)"), + [this](const httplib::Request & req, httplib::Response & res) { + fault_handlers_->handle_get_component_snapshots(req, res); }); // Single function (capabilities) - must be after more specific routes srv->Get((api_path("/functions") + R"(/([^/]+)$)"), [this](const httplib::Request & req, httplib::Response & res) { - function_handlers_->handle_get_function(req, res); + discovery_handlers_->handle_get_function(req, res); }); // Components srv->Get(api_path("/components"), [this](const httplib::Request & req, httplib::Response & res) { - component_handlers_->handle_list_components(req, res); + discovery_handlers_->handle_list_components(req, res); }); // Area components srv->Get((api_path("/areas") + R"(/([^/]+)/components)"), [this](const httplib::Request & req, httplib::Response & res) { - area_handlers_->handle_area_components(req, res); + discovery_handlers_->handle_area_components(req, res); }); // Area subareas (relationship endpoint) srv->Get((api_path("/areas") + R"(/([^/]+)/subareas$)"), [this](const httplib::Request & req, httplib::Response & res) { - area_handlers_->handle_get_subareas(req, res); + discovery_handlers_->handle_get_subareas(req, res); }); // Area contains srv->Get((api_path("/areas") + R"(/([^/]+)/contains$)"), [this](const httplib::Request & req, httplib::Response & res) { - area_handlers_->handle_get_contains(req, res); + discovery_handlers_->handle_get_contains(req, res); + }); + + // Area data item (specific topic) - register before /areas/{id}/data + srv->Get((api_path("/areas") + R"(/([^/]+)/data/(.+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + data_handlers_->handle_get_data_item(req, res); + }); + + // Area data write (PUT) - publish data to topic + srv->Put((api_path("/areas") + R"(/([^/]+)/data/(.+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + data_handlers_->handle_put_data_item(req, res); + }); + + // Area data (aggregated from contained components) + srv->Get((api_path("/areas") + R"(/([^/]+)/data$)"), [this](const httplib::Request & req, httplib::Response & res) { + data_handlers_->handle_list_data(req, res); + }); + + // Area operations + srv->Get((api_path("/areas") + R"(/([^/]+)/operations$)"), + [this](const httplib::Request & req, httplib::Response & res) { + operation_handlers_->handle_list_operations(req, res); + }); + + // Area operation details (GET) - get single operation info + srv->Get((api_path("/areas") + R"(/([^/]+)/operations/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + operation_handlers_->handle_get_operation(req, res); + }); + + // Execution endpoints for areas + srv->Post((api_path("/areas") + R"(/([^/]+)/operations/([^/]+)/executions$)"), + [this](const httplib::Request & req, httplib::Response & res) { + operation_handlers_->handle_create_execution(req, res); + }); + + srv->Get((api_path("/areas") + R"(/([^/]+)/operations/([^/]+)/executions$)"), + [this](const httplib::Request & req, httplib::Response & res) { + operation_handlers_->handle_list_executions(req, res); + }); + + srv->Get((api_path("/areas") + R"(/([^/]+)/operations/([^/]+)/executions/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + operation_handlers_->handle_get_execution(req, res); + }); + + srv->Put((api_path("/areas") + R"(/([^/]+)/operations/([^/]+)/executions/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + operation_handlers_->handle_update_execution(req, res); + }); + + srv->Delete((api_path("/areas") + R"(/([^/]+)/operations/([^/]+)/executions/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + operation_handlers_->handle_cancel_execution(req, res); + }); + + // Area configurations + srv->Get((api_path("/areas") + R"(/([^/]+)/configurations$)"), + [this](const httplib::Request & req, httplib::Response & res) { + config_handlers_->handle_list_configurations(req, res); + }); + + srv->Get((api_path("/areas") + R"(/([^/]+)/configurations/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + config_handlers_->handle_get_configuration(req, res); + }); + + srv->Put((api_path("/areas") + R"(/([^/]+)/configurations/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + config_handlers_->handle_set_configuration(req, res); + }); + + srv->Delete((api_path("/areas") + R"(/([^/]+)/configurations/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + config_handlers_->handle_delete_configuration(req, res); + }); + + srv->Delete((api_path("/areas") + R"(/([^/]+)/configurations$)"), + [this](const httplib::Request & req, httplib::Response & res) { + config_handlers_->handle_delete_all_configurations(req, res); + }); + + // Area faults + srv->Get((api_path("/areas") + R"(/([^/]+)/faults$)"), [this](const httplib::Request & req, httplib::Response & res) { + fault_handlers_->handle_list_faults(req, res); + }); + + srv->Get((api_path("/areas") + R"(/([^/]+)/faults/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + fault_handlers_->handle_get_fault(req, res); + }); + + srv->Delete((api_path("/areas") + R"(/([^/]+)/faults/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + fault_handlers_->handle_clear_fault(req, res); + }); + + srv->Delete((api_path("/areas") + R"(/([^/]+)/faults$)"), + [this](const httplib::Request & req, httplib::Response & res) { + fault_handlers_->handle_clear_all_faults(req, res); + }); + + srv->Get((api_path("/areas") + R"(/([^/]+)/faults/([^/]+)/snapshots$)"), + [this](const httplib::Request & req, httplib::Response & res) { + fault_handlers_->handle_get_component_snapshots(req, res); }); // Single area (capabilities) - must be after more specific routes srv->Get((api_path("/areas") + R"(/([^/]+)$)"), [this](const httplib::Request & req, httplib::Response & res) { - area_handlers_->handle_get_area(req, res); + discovery_handlers_->handle_get_area(req, res); }); // Component topic data (specific topic) - register before general route // Use (.+) for topic_name to accept slashes from percent-encoded URLs (%2F -> /) srv->Get((api_path("/components") + R"(/([^/]+)/data/(.+)$)"), [this](const httplib::Request & req, httplib::Response & res) { - component_handlers_->handle_component_topic_data(req, res); + data_handlers_->handle_get_data_item(req, res); }); // Component data (all topics) srv->Get((api_path("/components") + R"(/([^/]+)/data$)"), [this](const httplib::Request & req, httplib::Response & res) { - component_handlers_->handle_component_data(req, res); + data_handlers_->handle_list_data(req, res); }); // Component subcomponents (relationship endpoint) srv->Get((api_path("/components") + R"(/([^/]+)/subcomponents$)"), [this](const httplib::Request & req, httplib::Response & res) { - component_handlers_->handle_get_subcomponents(req, res); + discovery_handlers_->handle_get_subcomponents(req, res); }); // Component hosts srv->Get((api_path("/components") + R"(/([^/]+)/hosts$)"), [this](const httplib::Request & req, httplib::Response & res) { - component_handlers_->handle_get_hosts(req, res); + discovery_handlers_->handle_get_hosts(req, res); }); // Component depends-on (relationship endpoint) srv->Get((api_path("/components") + R"(/([^/]+)/depends-on$)"), [this](const httplib::Request & req, httplib::Response & res) { - component_handlers_->handle_get_depends_on(req, res); + discovery_handlers_->handle_component_depends_on(req, res); }); // Single component (capabilities) - must be after more specific routes srv->Get((api_path("/components") + R"(/([^/]+)$)"), [this](const httplib::Request & req, httplib::Response & res) { - component_handlers_->handle_get_component(req, res); + discovery_handlers_->handle_get_component(req, res); }); // Component topic publish (PUT) // Use (.+) for topic_name to accept slashes from percent-encoded URLs (%2F -> /) srv->Put((api_path("/components") + R"(/([^/]+)/data/(.+)$)"), [this](const httplib::Request & req, httplib::Response & res) { - component_handlers_->handle_component_topic_publish(req, res); + data_handlers_->handle_put_data_item(req, res); }); // List component operations (GET) - list all services and actions for a component 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 18d2c0d..d53c72f 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 @@ -71,6 +71,11 @@ void ThreadSafeEntityCache::update_functions(std::vector functions) { rebuild_relationship_indexes(); } +void ThreadSafeEntityCache::update_topic_types(std::unordered_map topic_types) { + std::unique_lock lock(mutex_); + topic_type_cache_ = std::move(topic_types); +} + // ============================================================================ // Reader methods - List all // ============================================================================ @@ -95,6 +100,15 @@ std::vector ThreadSafeEntityCache::get_functions() const { return functions_; } +std::string ThreadSafeEntityCache::get_topic_type(const std::string & topic_name) const { + std::shared_lock lock(mutex_); + auto it = topic_type_cache_.find(topic_name); + if (it != topic_type_cache_.end()) { + return it->second; + } + return ""; +} + // ============================================================================ // Reader methods - Get by ID // ============================================================================ @@ -628,4 +642,257 @@ void ThreadSafeEntityCache::collect_operations_from_component(size_t comp_index, } } +// ============================================================================ +// Data aggregation methods +// ============================================================================ + +AggregatedData ThreadSafeEntityCache::get_entity_data(const std::string & entity_id) const { + // find_entity takes its own lock, so we don't need one here + auto entity_ref = find_entity(entity_id); + if (!entity_ref) { + return {}; + } + + // Each get_*_data method takes its own lock + switch (entity_ref->type) { + case SovdEntityType::APP: + return get_app_data(entity_id); + case SovdEntityType::COMPONENT: + return get_component_data(entity_id); + case SovdEntityType::AREA: + return get_area_data(entity_id); + case SovdEntityType::FUNCTION: + return get_function_data(entity_id); + default: + return {}; + } +} + +AggregatedData ThreadSafeEntityCache::get_app_data(const std::string & app_id) const { + std::shared_lock lock(mutex_); + + auto it = app_index_.find(app_id); + if (it == app_index_.end()) { + return {}; + } + + AggregatedData result; + result.aggregation_level = "app"; + result.is_aggregated = false; + + std::unordered_set seen_topics; + collect_topics_from_app(it->second, seen_topics, result); + + return result; +} + +AggregatedData ThreadSafeEntityCache::get_component_data(const std::string & component_id) const { + std::shared_lock lock(mutex_); + + auto comp_it = component_index_.find(component_id); + if (comp_it == component_index_.end()) { + return {}; + } + + AggregatedData result; + result.aggregation_level = "component"; + + std::unordered_set seen_topics; + + // Collect from component itself + collect_topics_from_component(comp_it->second, seen_topics, result); + + // Collect from hosted apps + auto apps_it = component_to_apps_.find(component_id); + if (apps_it != component_to_apps_.end()) { + collect_topics_from_apps(apps_it->second, seen_topics, result); + result.is_aggregated = !apps_it->second.empty(); + } + + return result; +} + +AggregatedData ThreadSafeEntityCache::get_area_data(const std::string & area_id) const { + std::shared_lock lock(mutex_); + + auto area_it = area_index_.find(area_id); + if (area_it == area_index_.end()) { + return {}; + } + + AggregatedData result; + result.aggregation_level = "area"; + result.is_aggregated = true; + result.source_ids.push_back(area_id); + + std::unordered_set seen_topics; + + // Collect from all components in this area **and its subareas** (recursive) + std::vector component_indices; + std::unordered_set visited_areas; + std::vector pending_areas; + pending_areas.push_back(area_id); + + while (!pending_areas.empty()) { + const std::string current_area = pending_areas.back(); + pending_areas.pop_back(); + + // Skip already-visited areas to prevent infinite loops in case of cycles + if (!visited_areas.insert(current_area).second) { + continue; + } + + // Collect components directly associated with this area + auto comps_it = area_to_components_.find(current_area); + if (comps_it != area_to_components_.end()) { + component_indices.insert(component_indices.end(), comps_it->second.begin(), comps_it->second.end()); + } + + // Traverse into subareas + auto subareas_it = area_to_subareas_.find(current_area); + if (subareas_it != area_to_subareas_.end()) { + for (size_t subarea_idx : subareas_it->second) { + if (subarea_idx < areas_.size()) { + pending_areas.push_back(areas_[subarea_idx].id); + } + } + } + } + + for (size_t comp_idx : component_indices) { + collect_topics_from_component(comp_idx, seen_topics, result); + + // Also collect from apps hosted on each component + if (comp_idx < components_.size()) { + auto apps_it = component_to_apps_.find(components_[comp_idx].id); + if (apps_it != component_to_apps_.end()) { + collect_topics_from_apps(apps_it->second, seen_topics, result); + } + } + } + + return result; +} + +AggregatedData ThreadSafeEntityCache::get_function_data(const std::string & function_id) const { + std::shared_lock lock(mutex_); + + auto func_it = function_index_.find(function_id); + if (func_it == function_index_.end()) { + return {}; + } + + AggregatedData result; + result.aggregation_level = "function"; + result.is_aggregated = true; + result.source_ids.push_back(function_id); + + std::unordered_set seen_topics; + + // Collect from all apps implementing this function + auto apps_it = function_to_apps_.find(function_id); + if (apps_it != function_to_apps_.end()) { + collect_topics_from_apps(apps_it->second, seen_topics, result); + } + + return result; +} + +// ============================================================================ +// Data aggregation helpers +// ============================================================================ + +void ThreadSafeEntityCache::collect_topics_from_app(size_t app_index, std::unordered_set & seen_topics, + AggregatedData & result) const { + if (app_index >= apps_.size()) { + return; + } + + const auto & app = apps_[app_index]; + result.source_ids.push_back(app.id); + + // Publishers + for (const auto & topic : app.topics.publishes) { + auto [_, inserted] = seen_topics.insert(topic); + if (inserted) { + result.topics.push_back({topic, "", "publish"}); + } else { + // Topic already seen as subscriber - update direction to "both" + for (auto & t : result.topics) { + if (t.name == topic && t.direction == "subscribe") { + t.direction = "both"; + break; + } + } + } + } + + // Subscribers + for (const auto & topic : app.topics.subscribes) { + auto [_, inserted] = seen_topics.insert(topic); + if (inserted) { + result.topics.push_back({topic, "", "subscribe"}); + } else { + // Topic already seen - might be both pub and sub, update direction + for (auto & t : result.topics) { + if (t.name == topic && t.direction == "publish") { + t.direction = "both"; + break; + } + } + } + } +} + +void ThreadSafeEntityCache::collect_topics_from_apps(const std::vector & app_indexes, + std::unordered_set & seen_topics, + AggregatedData & result) const { + for (size_t idx : app_indexes) { + collect_topics_from_app(idx, seen_topics, result); + } +} + +void ThreadSafeEntityCache::collect_topics_from_component(size_t comp_index, + std::unordered_set & seen_topics, + AggregatedData & result) const { + if (comp_index >= components_.size()) { + return; + } + + const auto & comp = components_[comp_index]; + result.source_ids.push_back(comp.id); + + // Publishers + for (const auto & topic : comp.topics.publishes) { + auto [_, inserted] = seen_topics.insert(topic); + if (inserted) { + result.topics.push_back({topic, "", "publish"}); + } else { + // Topic already seen as subscriber - update direction to "both" + for (auto & t : result.topics) { + if (t.name == topic && t.direction == "subscribe") { + t.direction = "both"; + break; + } + } + } + } + + // Subscribers + for (const auto & topic : comp.topics.subscribes) { + auto [_, inserted] = seen_topics.insert(topic); + if (inserted) { + result.topics.push_back({topic, "", "subscribe"}); + } else { + // Topic already seen - might be both pub and sub, update direction + for (auto & t : result.topics) { + if (t.name == topic && t.direction == "publish") { + t.direction = "both"; + break; + } + } + } + } +} + } // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/test/test_entity_resource_model.cpp b/src/ros2_medkit_gateway/test/test_entity_resource_model.cpp index 64bcbf3..2c731bf 100644 --- a/src/ros2_medkit_gateway/test/test_entity_resource_model.cpp +++ b/src/ros2_medkit_gateway/test/test_entity_resource_model.cpp @@ -598,6 +598,128 @@ TEST_F(AggregationServiceTest, GetOperationsByIdAutoDetectsType) { EXPECT_EQ(result.aggregation_level, "app"); } +// ============================================================================ +// Data Aggregation Tests +// ============================================================================ + +class DataAggregationTest : public ::testing::Test { + protected: + void SetUp() override { + // Create a hierarchy: + // - Area: perception + // - Component: sensor_stack + // - App: camera_driver (publishes /camera/image, subscribes /camera/enable) + // - App: lidar_proc (publishes /lidar/points, subscribes /camera/image) + areas_ = {make_area("perception", "Perception Area")}; + + components_.push_back(make_component("sensor_stack", "Sensor Stack", "perception")); + components_[0].topics.publishes = {"/common/diagnostics"}; + components_[0].topics.subscribes = {"/common/clock"}; + + apps_.push_back(make_app_minimal("camera_driver", "sensor_stack")); + apps_[0].topics.publishes = {"/camera/image", "/camera/info"}; + apps_[0].topics.subscribes = {"/camera/enable"}; + + apps_.push_back(make_app_minimal("lidar_proc", "sensor_stack")); + apps_[1].topics.publishes = {"/lidar/points"}; + apps_[1].topics.subscribes = {"/camera/image"}; // Same topic that camera_driver publishes + + cache_.update_all(areas_, components_, apps_, {}); + } + + ThreadSafeEntityCache cache_; + std::vector areas_; + std::vector components_; + std::vector apps_; +}; + +TEST_F(DataAggregationTest, AppDataReturnsOwnTopicsOnly) { + auto result = cache_.get_app_data("camera_driver"); + + EXPECT_FALSE(result.is_aggregated); + EXPECT_EQ(result.aggregation_level, "app"); + EXPECT_EQ(result.source_ids.size(), 1); + EXPECT_EQ(result.source_ids[0], "camera_driver"); + + // camera_driver: 2 publishes + 1 subscribes = 3 topics + EXPECT_EQ(result.topics.size(), 3); + + // Check at least one publish and one subscribe + bool has_publish = false; + bool has_subscribe = false; + for (const auto & topic : result.topics) { + if (topic.direction == "publish") { + has_publish = true; + } + if (topic.direction == "subscribe") { + has_subscribe = true; + } + } + EXPECT_TRUE(has_publish); + EXPECT_TRUE(has_subscribe); +} + +TEST_F(DataAggregationTest, ComponentDataAggregatesFromHostedApps) { + auto result = cache_.get_component_data("sensor_stack"); + + EXPECT_TRUE(result.is_aggregated); + EXPECT_EQ(result.aggregation_level, "component"); + // Sources: component + 2 apps = 3 + EXPECT_EQ(result.source_ids.size(), 3); + + // Component topics: /common/diagnostics (pub), /common/clock (sub) + // camera_driver: /camera/image (pub), /camera/info (pub), /camera/enable (sub) + // lidar_proc: /lidar/points (pub), /camera/image (sub - already seen as pub) + // Total unique: 6 topics (/camera/image appears twice, merged as "both") + EXPECT_GE(result.topics.size(), 5); +} + +TEST_F(DataAggregationTest, DirectionMergesToBothWhenPubAndSub) { + auto result = cache_.get_component_data("sensor_stack"); + + // /camera/image is published by camera_driver and subscribed by lidar_proc + // Should be merged to direction="both" + bool found_camera_image = false; + for (const auto & topic : result.topics) { + if (topic.name == "/camera/image") { + found_camera_image = true; + EXPECT_EQ(topic.direction, "both"); + break; + } + } + EXPECT_TRUE(found_camera_image); +} + +TEST_F(DataAggregationTest, AreaDataAggregatesFromAllComponents) { + auto result = cache_.get_area_data("perception"); + + EXPECT_TRUE(result.is_aggregated); + EXPECT_EQ(result.aggregation_level, "area"); + EXPECT_GE(result.source_ids.size(), 1); // At least area itself + + // Should contain topics from sensor_stack and its apps + EXPECT_GE(result.topics.size(), 5); +} + +TEST_F(DataAggregationTest, GetEntityDataAutoDetectsType) { + auto app_result = cache_.get_entity_data("camera_driver"); + EXPECT_EQ(app_result.aggregation_level, "app"); + + auto comp_result = cache_.get_entity_data("sensor_stack"); + EXPECT_EQ(comp_result.aggregation_level, "component"); + + auto area_result = cache_.get_entity_data("perception"); + EXPECT_EQ(area_result.aggregation_level, "area"); +} + +TEST_F(DataAggregationTest, UnknownEntityReturnsEmptyData) { + auto result = cache_.get_entity_data("nonexistent"); + + EXPECT_TRUE(result.topics.empty()); + EXPECT_TRUE(result.source_ids.empty()); + EXPECT_TRUE(result.aggregation_level.empty()); +} + int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); diff --git a/src/ros2_medkit_gateway/test/test_integration.test.py b/src/ros2_medkit_gateway/test/test_integration.test.py index 031da05..57a9d61 100644 --- a/src/ros2_medkit_gateway/test/test_integration.test.py +++ b/src/ros2_medkit_gateway/test/test_integration.test.py @@ -635,6 +635,29 @@ def test_06_area_components_nonexistent_error(self): print('✓ Nonexistent area error test passed') + def _ensure_app_data_ready(self, app_id: str, timeout: float = 10.0, interval: float = 0.2): + """ + Wait for an app's /data endpoint to become available. + + Workaround for discovery readiness race condition in CI. + Polls /apps/{app_id}/data directly since that's what tests depend on. + """ + start_time = time.time() + last_error = None + while time.time() - start_time < timeout: + try: + response = requests.get(f'{self.BASE_URL}/apps/{app_id}/data', timeout=2) + if response.status_code == 200: + return + last_error = f'Status {response.status_code}' + except requests.exceptions.RequestException as e: + last_error = str(e) + time.sleep(interval) + self.fail( + f'App {app_id} data not available after {timeout}s. ' + f'Last error: {last_error}' + ) + def test_07_app_data_powertrain_engine(self): """ Test GET /apps/{app_id}/data for engine temperature sensor app. @@ -643,6 +666,8 @@ def test_07_app_data_powertrain_engine(self): @verifies REQ_INTEROP_018 """ + # Ensure app is ready (handles discovery race condition) + self._ensure_app_data_ready('temp_sensor') # Get data from temp_sensor app (powertrain/engine) data = self._get_json('/apps/temp_sensor/data') self.assertIn('items', data) @@ -660,7 +685,7 @@ def test_07_app_data_powertrain_engine(self): self.assertIn('ros2', x_medkit) self.assertIn('direction', x_medkit['ros2']) direction = x_medkit['ros2']['direction'] - self.assertIn(direction, ['publish', 'subscribe']) + self.assertIn(direction, ['publish', 'subscribe', 'both']) print( f" - Topic: {topic_data['name']} ({direction})" ) @@ -673,6 +698,8 @@ def test_08_app_data_chassis_brakes(self): @verifies REQ_INTEROP_018 """ + # Ensure app is ready (handles discovery race condition) + self._ensure_app_data_ready('pressure_sensor') # Get data from pressure_sensor app (chassis/brakes) data = self._get_json('/apps/pressure_sensor/data') self.assertIn('items', data) @@ -698,6 +725,8 @@ def test_09_app_data_body_door(self): @verifies REQ_INTEROP_018 """ + # Ensure app is ready (handles discovery race condition) + self._ensure_app_data_ready('status_sensor') # Get data from status_sensor app (body/door/front_left) data = self._get_json('/apps/status_sensor/data') self.assertIn('items', data) @@ -723,6 +752,8 @@ def test_10_app_data_structure(self): @verifies REQ_INTEROP_018 """ + # Ensure app is ready (handles discovery race condition) + self._ensure_app_data_ready('temp_sensor') data = self._get_json('/apps/temp_sensor/data') self.assertIn('items', data) items = data['items'] @@ -741,7 +772,7 @@ def test_10_app_data_structure(self): self.assertIsInstance( first_item['name'], str, "'name' should be a string" ) - self.assertIn(x_medkit['ros2']['direction'], ['publish', 'subscribe']) + self.assertIn(x_medkit['ros2']['direction'], ['publish', 'subscribe', 'both']) print('✓ App data structure test passed') @@ -758,10 +789,10 @@ def test_11_app_nonexistent_error(self): data = response.json() self.assertIn('error_code', data) - self.assertEqual(data['message'], 'App not found') + self.assertEqual(data['message'], 'Entity not found') self.assertIn('parameters', data) - self.assertIn('app_id', data['parameters']) - self.assertEqual(data['parameters'].get('app_id'), 'nonexistent_app') + self.assertIn('entity_id', data['parameters']) + self.assertEqual(data['parameters'].get('entity_id'), 'nonexistent_app') print('✓ Nonexistent app error test passed') @@ -813,7 +844,7 @@ def test_13_invalid_app_id_special_chars(self): data = response.json() self.assertIn('error_code', data) - self.assertEqual(data['message'], 'Invalid app ID') + self.assertEqual(data['message'], 'Invalid entity ID') self.assertIn('parameters', data) self.assertIn('details', data['parameters']) @@ -903,7 +934,7 @@ def test_16_invalid_ids_with_special_chars(self): data = response.json() self.assertIn('error_code', data) - self.assertEqual(data['message'], 'Invalid app ID') + self.assertEqual(data['message'], 'Invalid entity ID') print('✓ Invalid IDs with special chars test passed') @@ -1090,10 +1121,10 @@ def test_22_component_topic_nonexistent_component_error(self): data = response.json() self.assertIn('error_code', data) - self.assertEqual(data['message'], 'Component not found') + self.assertEqual(data['message'], 'Entity not found') self.assertIn('parameters', data) - self.assertIn('component_id', data['parameters']) - self.assertEqual(data['parameters'].get('component_id'), 'nonexistent_component') + self.assertIn('entity_id', data['parameters']) + self.assertEqual(data['parameters'].get('entity_id'), 'nonexistent_component') print('✓ Component topic nonexistent component error test passed') @@ -1276,9 +1307,9 @@ def test_29_publish_nonexistent_component(self): data = response.json() self.assertIn('error_code', data) - self.assertEqual(data['message'], 'Component not found') + self.assertEqual(data['message'], 'Entity not found') self.assertIn('parameters', data) - self.assertEqual(data['parameters'].get('component_id'), 'nonexistent_component') + self.assertEqual(data['parameters'].get('entity_id'), 'nonexistent_component') print('✓ Publish nonexistent component test passed') @@ -3927,3 +3958,210 @@ def test_72_get_rosbag_happy_path(self): os.unlink(temp_path) print('✓ Get rosbag happy path test passed') + + # ========== Area Data Endpoints Tests (test_109-112) ========== + + def test_109_list_area_data(self): + """ + Test GET /areas/{area_id}/data returns aggregated topics for area. + + Areas aggregate data from all components and apps in their hierarchy. + The powertrain area should include topics from engine sensors. + + @verifies REQ_INTEROP_018 + """ + response = requests.get( + f'{self.BASE_URL}/areas/powertrain/data', + timeout=10 + ) + self.assertEqual(response.status_code, 200) + + data = response.json() + self.assertIn('items', data) + items = data['items'] + self.assertIsInstance(items, list) + + # Powertrain area should have topics from engine sensors + if len(items) > 0: + for topic_data in items: + self.assertIn('id', topic_data) + self.assertIn('name', topic_data) + self.assertIn('x-medkit', topic_data) + x_medkit = topic_data['x-medkit'] + self.assertIn('ros2', x_medkit) + self.assertIn('direction', x_medkit['ros2']) + direction = x_medkit['ros2']['direction'] + self.assertIn(direction, ['publish', 'subscribe', 'both']) + + # Should include aggregated_from in x-medkit showing which entities contributed + self.assertIn('x-medkit', data) + self.assertIn('aggregated_from', data['x-medkit']) + # Area itself should be in aggregated_from (for empty area 200 response) + self.assertIn('powertrain', data['x-medkit']['aggregated_from']) + + print(f'✓ Area data list test passed: {len(items)} topics for powertrain') + + def test_110_list_area_data_nonexistent(self): + """ + Test GET /areas/{area_id}/data returns 404 for nonexistent area. + + @verifies REQ_INTEROP_018 + """ + response = requests.get( + f'{self.BASE_URL}/areas/nonexistent_area/data', + timeout=10 + ) + self.assertEqual(response.status_code, 404) + + data = response.json() + self.assertIn('error_code', data) + self.assertEqual(data['message'], 'Entity not found') + self.assertIn('parameters', data) + self.assertIn('entity_id', data['parameters']) + self.assertEqual(data['parameters'].get('entity_id'), 'nonexistent_area') + + print('✓ Area data nonexistent test passed') + + def test_111_list_area_data_root(self): + """ + Test GET /areas/root/data returns all topics system-wide. + + The root area aggregates all entities in the system. + + @verifies REQ_INTEROP_018 + """ + response = requests.get( + f'{self.BASE_URL}/areas/root/data', + timeout=10 + ) + self.assertEqual(response.status_code, 200) + + data = response.json() + self.assertIn('items', data) + items = data['items'] + self.assertIsInstance(items, list) + + # Root area should include topics from all namespaces + # At minimum we should have engine temperature and RPM topics + topic_names = [item['name'] for item in items] + # Root aggregates ALL topics from the system + self.assertGreater(len(items), 0, 'Root area should have aggregated topics') + + print(f'✓ Area root data test passed: {len(items)} system-wide topics: {topic_names}') + + def test_112_list_area_data_empty(self): + """ + Test GET /areas/{area_id}/data returns 200 with empty items for area with no data. + + Some areas may exist but have no direct topics - they should return 200 + with empty items, not 404. The entity_id should be in aggregated_from. + + @verifies REQ_INTEROP_018 + """ + # First find an area that might be empty (leaf area with no topics) + # Use chassis area which should have brakes topics + response = requests.get( + f'{self.BASE_URL}/areas/chassis/data', + timeout=10 + ) + # Should return 200 regardless of whether area has topics + self.assertEqual(response.status_code, 200) + + data = response.json() + self.assertIn('items', data) + self.assertIsInstance(data['items'], list) + # aggregated_from should include the area itself + self.assertIn('x-medkit', data) + self.assertIn('aggregated_from', data['x-medkit']) + self.assertIn('chassis', data['x-medkit']['aggregated_from']) + + print(f'✓ Area data empty/valid test passed: {len(data["items"])} topics') + + # ========== Function Data Endpoints Tests (test_113-115) ========== + + def test_113_list_function_data(self): + """ + Test GET /functions/{function_id}/data returns data items for function. + + Functions are logical groupings and may aggregate data from multiple sources. + + @verifies REQ_INTEROP_018 + """ + # First get list of functions to find one that exists + funcs_response = requests.get(f'{self.BASE_URL}/functions', timeout=10) + if funcs_response.status_code != 200: + self.skipTest('No functions available for testing') + + funcs = funcs_response.json().get('items', []) + if len(funcs) == 0: + self.skipTest('No functions available for testing') + + # Use the first available function + func_id = funcs[0]['id'] + + response = requests.get( + f'{self.BASE_URL}/functions/{func_id}/data', + timeout=10 + ) + self.assertEqual(response.status_code, 200) + + data = response.json() + self.assertIn('items', data) + self.assertIsInstance(data['items'], list) + + # aggregated_from should include the function itself + self.assertIn('x-medkit', data) + self.assertIn('aggregated_from', data['x-medkit']) + self.assertIn(func_id, data['x-medkit']['aggregated_from']) + + print(f'✓ Function data list test passed: {len(data["items"])} topics for {func_id}') + + def test_114_list_function_data_nonexistent(self): + """ + Test GET /functions/{function_id}/data returns 404 for nonexistent function. + + @verifies REQ_INTEROP_018 + """ + response = requests.get( + f'{self.BASE_URL}/functions/nonexistent_function/data', + timeout=10 + ) + self.assertEqual(response.status_code, 404) + + data = response.json() + self.assertIn('error_code', data) + self.assertEqual(data['message'], 'Entity not found') + self.assertIn('parameters', data) + self.assertIn('entity_id', data['parameters']) + self.assertEqual(data['parameters'].get('entity_id'), 'nonexistent_function') + + print('✓ Function data nonexistent test passed') + + def test_115_list_function_data_invalid_id(self): + """ + Test GET /functions/{function_id}/data rejects invalid function IDs. + + @verifies REQ_INTEROP_018 + """ + invalid_ids = [ + 'func;drop', + 'func