diff --git a/README.md b/README.md index be3bf1dbd..2d2a49f03 100644 --- a/README.md +++ b/README.md @@ -55,6 +55,7 @@ For more examples, see our [Postman collection](postman/). - **🌐 REST API Gateway** β€” HTTP interface for integration with external tools and UIs - **πŸ“Š Health Modeling** β€” Track health state per entity for fleet-level observability - **πŸ”§ Easy Integration** β€” Works with existing ROS 2 nodes out of the box (Jazzy, Humble & Rolling) +- **πŸ“¦ Bulk Data Management** β€” Upload, download, list, and delete bulk data files (calibration, firmware, etc.) ## πŸ“– Overview diff --git a/docs/api/rest.rst b/docs/api/rest.rst index 85b5ab64e..d1e676fce 100644 --- a/docs/api/rest.rst +++ b/docs/api/rest.rst @@ -480,15 +480,17 @@ Query and manage faults. Bulk Data Endpoints ------------------- -Download large binary data (rosbags, logs) associated with entities. -All entity types are supported: apps, components, areas, functions, and nested entities. +Access, upload, and delete large binary data (rosbags, calibration files, firmware, etc.) +associated with entities. Read endpoints (GET) support all entity types. Write endpoints +(POST, DELETE) are supported for components and apps only. List Categories ~~~~~~~~~~~~~~~ ``GET /api/v1/{entity-path}/bulk-data`` -List available bulk-data categories for an entity. +List available bulk-data categories for an entity. Returns the union of rosbag categories +(from the fault manager) and configured categories (from ``bulk_data.categories``). **Supported entity paths:** @@ -510,7 +512,7 @@ List available bulk-data categories for an entity. .. code-block:: json { - "items": ["rosbags"] + "items": ["rosbags", "calibration", "firmware"] } List Bulk Data Items @@ -571,6 +573,95 @@ Download a specific bulk-data file. - **200 OK**: File content - **404 Not Found**: Entity, category, or bulk-data ID not found +Upload Bulk Data +~~~~~~~~~~~~~~~~ + +``POST /api/v1/{entity-path}/bulk-data/{category}`` + +Upload a new bulk-data file to the specified category. Files are sent as +``multipart/form-data``. The ``rosbags`` category is read-only and cannot be +used for uploads. + +**Supported entity types:** components, apps only. Areas and functions return 405. + +**Form Fields:** + +.. list-table:: + :header-rows: 1 + :widths: 20 15 65 + + * - Field + - Required + - Description + * - ``file`` + - Yes + - The file to upload (binary data with filename and content type). + * - ``description`` + - No + - Human-readable description of the file. + * - ``metadata`` + - No + - JSON string with arbitrary key-value metadata. + +**Example:** + +.. code-block:: bash + + curl -X POST http://localhost:8080/api/v1/components/motor_controller/bulk-data/calibration \ + -F "file=@calibration_data.bin;type=application/octet-stream" \ + -F "description=Motor calibration parameters v2.1" \ + -F 'metadata={"version": "2.1", "author": "engineer_01"}' + +**Response (201 Created):** + +.. code-block:: json + + { + "id": "calibration_1739612345000000000_ab12cd34", + "name": "calibration_data.bin", + "mimetype": "application/octet-stream", + "size": 4096, + "creation_date": "2026-03-15T14:30:00.000Z", + "description": "Motor calibration parameters v2.1", + "x-medkit": { + "version": "2.1", + "author": "engineer_01" + } + } + +**Response Headers:** + +- ``Location``: ``/api/v1/components/motor_controller/bulk-data/calibration/calibration_1739612345000000000_ab12cd34`` + +**Error Responses:** + +- **400 Bad Request**: Missing ``file`` field, unknown category, or ``rosbags`` category +- **405 Method Not Allowed**: Upload attempted on areas or functions +- **413 Payload Too Large**: File exceeds ``bulk_data.max_upload_size`` + +Delete Bulk Data +~~~~~~~~~~~~~~~~ + +``DELETE /api/v1/{entity-path}/bulk-data/{category}/{id}`` + +Delete a specific bulk-data item. The ``rosbags`` category is managed by the +fault manager and cannot be deleted via this endpoint. + +**Supported entity types:** components, apps only. Areas and functions return 405. + +**Example:** + +.. code-block:: bash + + curl -X DELETE http://localhost:8080/api/v1/components/motor_controller/bulk-data/calibration/calibration_1739612345000000000_ab12cd34 + +**Response Codes:** + +- **204 No Content**: Item deleted successfully +- **400 Bad Request**: ``rosbags`` category (managed by fault manager) +- **404 Not Found**: Entity, category, or bulk-data ID not found +- **405 Method Not Allowed**: Delete attempted on areas or functions + Authentication Endpoints ------------------------ diff --git a/docs/config/server.rst b/docs/config/server.rst index cd8f2afc0..aeb87a410 100644 --- a/docs/config/server.rst +++ b/docs/config/server.rst @@ -173,6 +173,50 @@ Performance Tuning Lower values provide faster updates but increase CPU usage. +Bulk Data Storage +----------------- + +Configure file-based bulk data storage for uploads (calibration files, firmware, etc.). +The ``rosbags`` category is always available via the Fault Manager and does not need +configuration. + +.. list-table:: + :header-rows: 1 + :widths: 30 10 25 35 + + * - Parameter + - Type + - Default + - Description + * - ``bulk_data.storage_dir`` + - string + - ``/tmp/ros2_medkit_bulk_data`` + - Base directory for uploaded files. Each entity gets a subdirectory. + * - ``bulk_data.max_upload_size`` + - int + - ``104857600`` + - Maximum upload file size in bytes (default: 100 MB). Set to 0 for unlimited. + * - ``bulk_data.categories`` + - string[] + - ``[]`` + - Allowed bulk data categories for upload/download (e.g., ``calibration``, ``firmware``). + +Example: + +.. code-block:: yaml + + ros2_medkit_gateway: + ros__parameters: + bulk_data: + storage_dir: "/var/ros2_medkit/bulk_data" + max_upload_size: 52428800 # 50 MB + categories: ["calibration", "firmware", "logs"] + +.. note:: + + The ``rosbags`` category is always available through the Fault Manager and cannot be + used for uploads or deletes. It is automatically included in the category list. + .. note:: The gateway uses native rclcpp APIs for all ROS 2 interactionsβ€”no ROS 2 CLI @@ -203,6 +247,11 @@ Complete Example allow_credentials: true max_age_seconds: 86400 + bulk_data: + storage_dir: "/var/ros2_medkit/bulk_data" + max_upload_size: 104857600 + categories: ["calibration", "firmware"] + See Also -------- diff --git a/docs/requirements/specs/bulkdata.rst b/docs/requirements/specs/bulkdata.rst index 36264aa0b..d0796d36a 100644 --- a/docs/requirements/specs/bulkdata.rst +++ b/docs/requirements/specs/bulkdata.rst @@ -33,15 +33,25 @@ BulkData .. req:: POST /{entity}/bulk-data/{category} :id: REQ_INTEROP_074 - :status: open - :tags: BulkData + :status: verified + :tags: BulkData, SOVD + :links: REQ_INTEROP_071 + + The endpoint shall upload new bulk data in the addressed category and create a + corresponding bulk-data resource on the entity. - The endpoint shall upload new bulk data in the addressed category and create a corresponding bulk-data resource on the entity. + Accepts multipart/form-data with a required ``file`` field and optional ``description`` + and ``metadata`` fields. Returns 201 Created with a Location header pointing to the new + resource. Supported for components and apps. The ``rosbags`` category is read-only. .. req:: DELETE /{entity}/bulk-data/{category}/{bulk-data-id} :id: REQ_INTEROP_075 - :status: open - :tags: BulkData + :status: verified + :tags: BulkData, SOVD + :links: REQ_INTEROP_071 The endpoint shall delete the addressed bulk-data item from the entity, if permitted. + Returns 204 No Content on success. Supported for components and apps. + The ``rosbags`` category is managed by the fault manager and cannot be deleted. + diff --git a/src/ros2_medkit_gateway/CMakeLists.txt b/src/ros2_medkit_gateway/CMakeLists.txt index e731bc2a0..74beb3fa7 100644 --- a/src/ros2_medkit_gateway/CMakeLists.txt +++ b/src/ros2_medkit_gateway/CMakeLists.txt @@ -116,6 +116,8 @@ add_library(gateway_lib STATIC src/http/handlers/bulkdata_handlers.cpp src/http/handlers/sse_fault_handler.cpp src/http/handlers/auth_handlers.cpp + # Bulk data storage + src/bulk_data_store.cpp # HTTP utilities src/http/x_medkit.cpp src/http/entity_path_utils.cpp @@ -333,6 +335,10 @@ if(BUILD_TESTING) ament_add_gtest(test_fault_handlers test/test_fault_handlers.cpp) target_link_libraries(test_fault_handlers gateway_lib) + # Add bulk data store tests + ament_add_gtest(test_bulk_data_store test/test_bulk_data_store.cpp) + target_link_libraries(test_bulk_data_store gateway_lib) + # Add bulk data handlers tests ament_add_gtest(test_bulkdata_handlers test/test_bulkdata_handlers.cpp) target_link_libraries(test_bulkdata_handlers gateway_lib) @@ -358,6 +364,7 @@ if(BUILD_TESTING) test_data_access_manager test_entity_path_utils test_fault_handlers + test_bulk_data_store test_bulkdata_handlers ) foreach(_target ${_test_targets}) @@ -424,6 +431,13 @@ if(BUILD_TESTING) TIMEOUT 120 ) + # Add bulk data upload/delete integration tests + add_launch_test( + test/test_bulkdata_upload.test.py + TARGET test_bulkdata_upload + TIMEOUT 120 + ) + # Demo automotive nodes add_executable(demo_engine_temp_sensor test/demo_nodes/engine_temp_sensor.cpp diff --git a/src/ros2_medkit_gateway/README.md b/src/ros2_medkit_gateway/README.md index b555f8f2c..f16e466a6 100644 --- a/src/ros2_medkit_gateway/README.md +++ b/src/ros2_medkit_gateway/README.md @@ -11,6 +11,7 @@ The ROS 2 Medkit Gateway exposes ROS 2 system information and data through a RES - **Area-based organization**: Groups nodes by namespace (e.g., `/powertrain`, `/chassis`, `/body`) - **REST API**: Standard HTTP/JSON interface - **Real-time updates**: Configurable cache refresh for up-to-date system state +- **Bulk Data Management**: Upload, download, list, and delete bulk data files (calibration, firmware, etc.) ## Endpoints @@ -55,6 +56,14 @@ All endpoints are prefixed with `/api/v1` for API versioning. - `DELETE /api/v1/components/{component_id}/configurations/{param}` - Reset parameter to default value - `DELETE /api/v1/components/{component_id}/configurations` - Reset all parameters to default values +### Bulk Data Endpoints + +- `GET /api/v1/{entity}/{id}/bulk-data` - List bulk-data categories (rosbags + configured) +- `GET /api/v1/{entity}/{id}/bulk-data/{category}` - List bulk-data items in a category +- `GET /api/v1/{entity}/{id}/bulk-data/{category}/{item_id}` - Download a bulk-data file +- `POST /api/v1/{entity}/{id}/bulk-data/{category}` - Upload bulk data (components/apps only) +- `DELETE /api/v1/{entity}/{id}/bulk-data/{category}/{item_id}` - Delete bulk data (components/apps only) + ### API Reference #### GET /api/v1/areas diff --git a/src/ros2_medkit_gateway/config/gateway_params.yaml b/src/ros2_medkit_gateway/config/gateway_params.yaml index 6b4746ae7..40c0070dc 100644 --- a/src/ros2_medkit_gateway/config/gateway_params.yaml +++ b/src/ros2_medkit_gateway/config/gateway_params.yaml @@ -64,8 +64,8 @@ ros2_medkit_gateway: allowed_origins: [""] # Allowed HTTP methods for CORS requests - # Default: ["GET", "PUT", "OPTIONS"] - allowed_methods: ["GET", "PUT", "OPTIONS"] + # Default: ["GET", "PUT", "POST", "DELETE", "OPTIONS"] + allowed_methods: ["GET", "PUT", "POST", "DELETE", "OPTIONS"] # Allowed headers in CORS requests # List the allowed headers explicitly (wildcard "*" is not supported) @@ -204,3 +204,22 @@ ros2_medkit_gateway: # Example: # clients: ["admin:admin_secret_123:admin", "viewer:viewer_pass:viewer"] clients: [""] + + # Bulk Data Storage Configuration + # Controls where uploaded bulk data files are stored and size limits + bulk_data: + # Base directory for uploaded files + # Created automatically if it doesn't exist + # Default: /tmp/ros2_medkit_bulk_data + storage_dir: "/tmp/ros2_medkit_bulk_data" + + # Maximum upload file size in bytes + # Also sets cpp-httplib set_payload_max_length() globally + # Default: 104857600 (100MB) + # Set to 0 for unlimited (not recommended in production) + max_upload_size: 104857600 + + # Allowed bulk data categories (besides "rosbags" which is always + # available via FaultManager) + # Example: ["calibration", "firmware", "comlogs", "snapshots"] + categories: [] diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/bulk_data_store.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/bulk_data_store.hpp new file mode 100644 index 000000000..0c3982560 --- /dev/null +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/bulk_data_store.hpp @@ -0,0 +1,151 @@ +// Copyright 2026 bburda +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace ros2_medkit_gateway { + +/** + * @brief Filesystem-based storage for uploaded bulk data files. + * + * Stores files in a directory structure: + * {storage_dir}/{entity_id}/{category}/{item_id}/ + * descriptor.json β€” metadata sidecar + * {original_filename} β€” payload + * + * Thread-safe: uses mutex for rename + descriptor write operations. + * Large payload writes happen outside the lock. + * + * Categories are configured at construction time. The "rosbags" category + * is NOT managed here β€” it is handled by FaultManager. + * + * @todo #215 Per-category config (BulkDataCategoryConfig): access mode + * (read-only/write-only/read-write), per-category max_file_size, source_path/upload_path + * templates, human-readable name. Currently categories are plain string IDs with a single + * global upload limit. See https://github.com/selfpatch/ros2_medkit/issues/215 + */ +class BulkDataStore { + public: + /** + * @brief Metadata descriptor for an uploaded bulk data item. + */ + struct ItemDescriptor { + std::string id; + std::string category; + std::string name; ///< Original filename + std::string mime_type; + size_t size{0}; + std::string created; ///< ISO 8601 timestamp + std::string description; + nlohmann::json metadata; + }; + + /** + * @brief Construct a BulkDataStore. + * @param storage_dir Base directory for uploaded files + * @param max_upload_bytes Global max upload size in bytes (0 = unlimited) + * @param categories List of allowed category names (besides "rosbags") + */ + BulkDataStore(const std::string & storage_dir, size_t max_upload_bytes, std::vector categories = {}); + + // === CRUD === + + /** + * @brief Upload a file. + * + * Uses atomic write: payload β†’ tmp file β†’ rename + write descriptor.json. + * + * @param entity_id Entity this file belongs to + * @param category Bulk data category (must be in configured list) + * @param filename Original filename + * @param content_type MIME type + * @param data File contents + * @param description Optional text description + * @param metadata Optional JSON metadata + * @return ItemDescriptor on success, error message on failure + */ + tl::expected store(const std::string & entity_id, const std::string & category, + const std::string & filename, const std::string & content_type, + const std::string & data, const std::string & description = "", + const nlohmann::json & metadata = {}); + + /** + * @brief Delete an uploaded item. + * @param entity_id Entity ID + * @param category Category name + * @param item_id Item ID to delete + * @return void on success, error message if not found + */ + tl::expected remove(const std::string & entity_id, const std::string & category, + const std::string & item_id); + + // === Queries === + + /// List configured categories (does NOT include "rosbags") + std::vector list_categories() const; + + /// List items in a category for an entity (scans filesystem) + std::vector list_items(const std::string & entity_id, const std::string & category) const; + + /// Get single item descriptor + std::optional get_item(const std::string & entity_id, const std::string & category, + const std::string & item_id) const; + + /// Get filesystem path to uploaded file (for streaming download) + std::optional get_file_path(const std::string & entity_id, const std::string & category, + const std::string & item_id) const; + + // === Validation === + + /// Check if category is in configured list + bool is_known_category(const std::string & category) const; + + /// Get max upload size in bytes + size_t max_upload_bytes() const { + return max_upload_bytes_; + } + + private: + std::string storage_dir_; + size_t max_upload_bytes_; + std::unordered_set categories_; + mutable std::mutex mutex_; + + /// Generate unique ID: {category}_{timestamp_ns}_{random_hex_8} + static std::string generate_id(const std::string & category); + + /// Get item directory: {storage_dir}/{entity_id}/{category}/{item_id}/ + std::filesystem::path item_dir(const std::string & entity_id, const std::string & category, + const std::string & item_id) const; + + /// Write descriptor.json sidecar. Returns false on I/O error. + static bool write_descriptor(const std::filesystem::path & dir, const ItemDescriptor & desc); + + /// Read descriptor.json sidecar + static std::optional read_descriptor(const std::filesystem::path & dir); + + /// Validate path component (reject traversal attacks) + static tl::expected validate_path_component(const std::string & value, const std::string & name); +}; + +} // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/gateway_node.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/gateway_node.hpp index 900285b59..140ee78d0 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/gateway_node.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/gateway_node.hpp @@ -24,6 +24,7 @@ #include #include "ros2_medkit_gateway/auth/auth_config.hpp" +#include "ros2_medkit_gateway/bulk_data_store.hpp" #include "ros2_medkit_gateway/config.hpp" #include "ros2_medkit_gateway/configuration_manager.hpp" #include "ros2_medkit_gateway/data_access_manager.hpp" @@ -78,6 +79,12 @@ class GatewayNode : public rclcpp::Node { */ FaultManager * get_fault_manager() const; + /** + * @brief Get the BulkDataStore instance + * @return Raw pointer to BulkDataStore (valid for lifetime of GatewayNode) + */ + BulkDataStore * get_bulk_data_store() const; + private: void refresh_cache(); void start_rest_server(); @@ -97,6 +104,7 @@ class GatewayNode : public rclcpp::Node { std::unique_ptr operation_mgr_; std::unique_ptr config_mgr_; std::unique_ptr fault_mgr_; + std::unique_ptr bulk_data_store_; std::unique_ptr rest_server_; // Cache with thread safety diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/error_codes.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/error_codes.hpp index b43d5a614..8c84a7a0e 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/error_codes.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/error_codes.hpp @@ -50,6 +50,9 @@ constexpr const char * ERR_INTERNAL_ERROR = "internal-error"; /// Collection not supported on entity type constexpr const char * ERR_COLLECTION_NOT_SUPPORTED = "collection-not-supported"; +/// Payload too large (used for file upload size limits) +constexpr const char * ERR_PAYLOAD_TOO_LARGE = "payload-too-large"; + /// Feature not implemented (SOVD 501 Not Implemented) constexpr const char * ERR_NOT_IMPLEMENTED = "not-implemented"; diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/bulkdata_handlers.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/bulkdata_handlers.hpp index 9a59e2781..05944bf8e 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/bulkdata_handlers.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/bulkdata_handlers.hpp @@ -78,6 +78,32 @@ class BulkDataHandlers { */ void handle_download(const httplib::Request & req, httplib::Response & res); + /** + * @brief POST {entity-path}/bulk-data/{category} - Upload bulk-data file. + * + * Accepts multipart/form-data with: + * - "file" (required): the file to upload + * - "description" (optional): text description + * - "metadata" (optional): JSON string with additional metadata + * + * Returns 201 with ItemDescriptor JSON on success. + * + * @param req HTTP request + * @param res HTTP response + */ + void handle_upload(const httplib::Request & req, httplib::Response & res); + + /** + * @brief DELETE {entity-path}/bulk-data/{category}/{id} - Delete bulk-data file. + * + * Removes an uploaded bulk-data item. Returns 204 on success, 404 if not found. + * Only items uploaded via POST can be deleted (rosbags managed by fault system cannot). + * + * @param req HTTP request + * @param res HTTP response + */ + void handle_delete(const httplib::Request & req, httplib::Response & res); + /** * @brief Get MIME type for rosbag format. * @param format Storage format ("mcap", "sqlite3", "db3") diff --git a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/handler_context.hpp b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/handler_context.hpp index 25674c6d9..d54dfd163 100644 --- a/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/handler_context.hpp +++ b/src/ros2_medkit_gateway/include/ros2_medkit_gateway/http/handlers/handler_context.hpp @@ -89,6 +89,7 @@ struct EntityInfo { // Forward declarations class GatewayNode; class AuthManager; +class BulkDataStore; namespace handlers { @@ -101,12 +102,13 @@ namespace handlers { class HandlerContext { public: HandlerContext(GatewayNode * node, const CorsConfig & cors_config, const AuthConfig & auth_config, - const TlsConfig & tls_config, AuthManager * auth_manager) + const TlsConfig & tls_config, AuthManager * auth_manager, BulkDataStore * bulk_data_store = nullptr) : node_(node) , cors_config_(cors_config) , auth_config_(auth_config) , tls_config_(tls_config) - , auth_manager_(auth_manager) { + , auth_manager_(auth_manager) + , bulk_data_store_(bulk_data_store) { } /// Get gateway node @@ -134,6 +136,11 @@ class HandlerContext { return auth_manager_; } + /// Get bulk data store (may be nullptr if not configured) + BulkDataStore * bulk_data_store() const { + return bulk_data_store_; + } + /** * @brief Validate entity ID (component_id, area_id, etc.) * @param entity_id The ID to validate @@ -253,6 +260,7 @@ class HandlerContext { AuthConfig auth_config_; TlsConfig tls_config_; AuthManager * auth_manager_; + BulkDataStore * bulk_data_store_; }; } // namespace handlers 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 a7c20fd7e..b8054015f 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 @@ -16,10 +16,14 @@ #include +#include #include #include #include +#include +#include #include +#include #include "ros2_medkit_gateway/models/entity_types.hpp" @@ -163,4 +167,57 @@ inline std::string format_timestamp_ns(int64_t ns) { return result; } +/** + * @brief Stream file contents to HTTP response using chunked transfer. + * + * Generic utility for streaming any file to an HTTP response. The file path + * must point to an existing regular file (resolve rosbag directories etc. + * before calling this function). + * + * @param res HTTP response to write to + * @param file_path Path to an existing regular file + * @param content_type MIME type for Content-Type header + * @return true if successful, false if file could not be read + */ +inline bool stream_file_to_response(httplib::Response & res, const std::string & file_path, + const std::string & content_type) { + std::error_code ec; + auto file_size = std::filesystem::file_size(file_path, ec); + if (ec) { + return false; + } + + static constexpr size_t kChunkSize = 64 * 1024; // 64 KB chunks + + res.set_content_provider(static_cast(file_size), content_type, + [file_path](size_t offset, size_t length, httplib::DataSink & sink) -> bool { + std::ifstream file(file_path, std::ios::binary); + if (!file.is_open()) { + return false; + } + + file.seekg(static_cast(offset)); + if (!file.good()) { + return false; + } + + size_t remaining = length; + std::vector buf(std::min(remaining, kChunkSize)); + + while (remaining > 0 && file.good()) { + size_t to_read = std::min(remaining, kChunkSize); + file.read(buf.data(), static_cast(to_read)); + auto bytes_read = static_cast(file.gcount()); + if (bytes_read == 0) { + break; + } + sink.write(buf.data(), bytes_read); + remaining -= bytes_read; + } + + return remaining == 0; + }); + return true; +} + } // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/src/bulk_data_store.cpp b/src/ros2_medkit_gateway/src/bulk_data_store.cpp new file mode 100644 index 000000000..3b0b08421 --- /dev/null +++ b/src/ros2_medkit_gateway/src/bulk_data_store.cpp @@ -0,0 +1,337 @@ +// 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/bulk_data_store.hpp" + +#include +#include +#include +#include +#include +#include + +#include "ros2_medkit_gateway/http/http_utils.hpp" + +namespace ros2_medkit_gateway { + +BulkDataStore::BulkDataStore(const std::string & storage_dir, size_t max_upload_bytes, + std::vector categories) + : storage_dir_(storage_dir), max_upload_bytes_(max_upload_bytes) { + for (auto & cat : categories) { + categories_.insert(std::move(cat)); + } + // Ensure storage directory exists + std::error_code ec; + std::filesystem::create_directories(storage_dir_, ec); +} + +// --- Validation --- + +tl::expected BulkDataStore::validate_path_component(const std::string & value, + const std::string & name) { + if (value.empty()) { + return tl::unexpected(name + " cannot be empty"); + } + // Reject path traversal and unsafe characters + if (value.find("..") != std::string::npos) { + return tl::unexpected(name + " contains invalid sequence '..'"); + } + if (value.find('/') != std::string::npos || value.find('\\') != std::string::npos) { + return tl::unexpected(name + " contains path separator"); + } + if (value.find('\0') != std::string::npos) { + return tl::unexpected(name + " contains null byte"); + } + if (value == ".") { + return tl::unexpected(name + " cannot be '.'"); + } + return {}; +} + +bool BulkDataStore::is_known_category(const std::string & category) const { + return categories_.count(category) > 0; +} + +std::vector BulkDataStore::list_categories() const { + return {categories_.begin(), categories_.end()}; +} + +// --- ID generation --- + +std::string BulkDataStore::generate_id(const std::string & category) { + // {category}_{timestamp_ns}_{random_hex_8} + auto now = std::chrono::system_clock::now(); + auto ns = std::chrono::duration_cast(now.time_since_epoch()).count(); + + // Generate 8 hex chars from random + static thread_local std::mt19937 gen(std::random_device{}()); + std::uniform_int_distribution dist(0, 0xFFFFFFFF); + uint32_t rand_val = dist(gen); + + std::ostringstream oss; + oss << category << "_" << ns << "_" << std::hex << std::setfill('0') << std::setw(8) << rand_val; + return oss.str(); +} + +// --- Directory helpers --- + +std::filesystem::path BulkDataStore::item_dir(const std::string & entity_id, const std::string & category, + const std::string & item_id) const { + return std::filesystem::path(storage_dir_) / entity_id / category / item_id; +} + +// --- Descriptor I/O --- + +bool BulkDataStore::write_descriptor(const std::filesystem::path & dir, const ItemDescriptor & desc) { + nlohmann::json j; + j["id"] = desc.id; + j["category"] = desc.category; + j["name"] = desc.name; + j["mime_type"] = desc.mime_type; + j["size"] = desc.size; + j["created"] = desc.created; + j["description"] = desc.description; + if (!desc.metadata.empty()) { + j["metadata"] = desc.metadata; + } + + auto path = dir / "descriptor.json"; + std::ofstream ofs(path); + if (!ofs.is_open()) { + return false; + } + ofs << j.dump(2); + ofs.flush(); + return ofs.good(); +} + +std::optional BulkDataStore::read_descriptor(const std::filesystem::path & dir) { + auto path = dir / "descriptor.json"; + if (!std::filesystem::is_regular_file(path)) { + return std::nullopt; + } + + std::ifstream ifs(path); + if (!ifs.is_open()) { + return std::nullopt; + } + + try { + nlohmann::json j = nlohmann::json::parse(ifs); + ItemDescriptor desc; + desc.id = j.value("id", ""); + desc.category = j.value("category", ""); + desc.name = j.value("name", ""); + desc.mime_type = j.value("mime_type", ""); + desc.size = j.value("size", static_cast(0)); + desc.created = j.value("created", ""); + desc.description = j.value("description", ""); + if (j.contains("metadata")) { + desc.metadata = j["metadata"]; + } + return desc; + } catch (...) { + return std::nullopt; + } +} + +// --- CRUD --- + +tl::expected +BulkDataStore::store(const std::string & entity_id, const std::string & category, const std::string & filename, + const std::string & content_type, const std::string & data, const std::string & description, + const nlohmann::json & metadata) { + // Validate inputs + if (auto v = validate_path_component(entity_id, "entity_id"); !v) { + return tl::unexpected(v.error()); + } + if (auto v = validate_path_component(category, "category"); !v) { + return tl::unexpected(v.error()); + } + + // Validate category is known + if (!is_known_category(category)) { + return tl::unexpected("Unknown category: " + category); + } + + // Check upload size limit + if (max_upload_bytes_ > 0 && data.size() > max_upload_bytes_) { + return tl::unexpected("File size " + std::to_string(data.size()) + " exceeds maximum upload limit " + + std::to_string(max_upload_bytes_)); + } + + // Generate unique ID + auto id = generate_id(category); + + // Create item directory + auto dir = item_dir(entity_id, category, id); + std::error_code ec; + std::filesystem::create_directories(dir, ec); + if (ec) { + return tl::unexpected("Failed to create directory: " + ec.message()); + } + + // Sanitize filename (use "upload" if empty, strip path components) + std::string safe_filename = filename.empty() ? "upload" : std::filesystem::path(filename).filename().string(); + if (safe_filename.empty()) { + safe_filename = "upload"; + } + + // Step 1: Write payload to temp file (outside lock) + auto tmp_path = dir / ".data.tmp"; + { + std::ofstream ofs(tmp_path, std::ios::binary); + if (!ofs.is_open()) { + return tl::unexpected("Failed to open temp file for writing"); + } + ofs.write(data.data(), static_cast(data.size())); + if (!ofs.good()) { + return tl::unexpected("Failed to write payload data"); + } + } + + // Build descriptor + auto now = std::chrono::system_clock::now(); + auto ns = std::chrono::duration_cast(now.time_since_epoch()).count(); + + ItemDescriptor desc; + desc.id = id; + desc.category = category; + desc.name = safe_filename; + desc.mime_type = content_type.empty() ? "application/octet-stream" : content_type; + desc.size = data.size(); + desc.created = format_timestamp_ns(ns); + desc.description = description; + desc.metadata = metadata; + + // Step 2: Rename + write descriptor (under lock) + { + std::lock_guard lock(mutex_); + auto final_path = dir / safe_filename; + std::filesystem::rename(tmp_path, final_path, ec); + if (ec) { + // Fallback: try copy + remove (cross-device rename) + std::filesystem::copy_file(tmp_path, final_path, ec); + if (ec) { + // Clean up temp file on failure + std::error_code cleanup_ec; + std::filesystem::remove(tmp_path, cleanup_ec); + return tl::unexpected("Failed to finalize file: " + ec.message()); + } + std::filesystem::remove(tmp_path, ec); + } + if (!write_descriptor(dir, desc)) { + // Clean up the payload file we just moved β€” the item is incomplete + std::error_code cleanup_ec; + std::filesystem::remove_all(dir, cleanup_ec); + return tl::unexpected("Failed to write descriptor"); + } + } + + return desc; +} + +tl::expected BulkDataStore::remove(const std::string & entity_id, const std::string & category, + const std::string & item_id) { + if (auto err = validate_path_component(entity_id, "entity_id"); !err) { + return tl::unexpected(err.error()); + } + if (auto err = validate_path_component(category, "category"); !err) { + return tl::unexpected(err.error()); + } + if (auto err = validate_path_component(item_id, "item_id"); !err) { + return tl::unexpected(err.error()); + } + + auto dir = item_dir(entity_id, category, item_id); + + // NOTE: The lock is held for the entire remove_all() which blocks other store operations. + // For our current use case this is fine (small directories, rare deletes). If this becomes + // a bottleneck, consider renaming the dir to a `.deleting_` prefix under lock, then + // removing outside the lock. + std::lock_guard lock(mutex_); + if (!std::filesystem::is_directory(dir)) { + return tl::unexpected("Bulk-data item not found: " + item_id); + } + + std::error_code ec; + std::filesystem::remove_all(dir, ec); + if (ec) { + return tl::unexpected("Failed to delete item: " + ec.message()); + } + + return {}; +} + +// --- Queries --- + +std::vector BulkDataStore::list_items(const std::string & entity_id, + const std::string & category) const { + std::vector items; + + auto cat_dir = std::filesystem::path(storage_dir_) / entity_id / category; + + std::lock_guard lock(mutex_); + if (!std::filesystem::is_directory(cat_dir)) { + return items; + } + + for (const auto & entry : std::filesystem::directory_iterator(cat_dir)) { + if (entry.is_directory()) { + auto desc = read_descriptor(entry.path()); + if (desc) { + items.push_back(std::move(*desc)); + } + } + } + + return items; +} + +std::optional BulkDataStore::get_item(const std::string & entity_id, + const std::string & category, + const std::string & item_id) const { + auto dir = item_dir(entity_id, category, item_id); + + std::lock_guard lock(mutex_); + if (!std::filesystem::is_directory(dir)) { + return std::nullopt; + } + + return read_descriptor(dir); +} + +std::optional BulkDataStore::get_file_path(const std::string & entity_id, const std::string & category, + const std::string & item_id) const { + auto dir = item_dir(entity_id, category, item_id); + + std::lock_guard lock(mutex_); + if (!std::filesystem::is_directory(dir)) { + return std::nullopt; + } + + // Find the payload file (not descriptor.json and not .data.tmp) + for (const auto & entry : std::filesystem::directory_iterator(dir)) { + if (entry.is_regular_file()) { + auto fname = entry.path().filename().string(); + if (fname != "descriptor.json" && fname != ".data.tmp") { + return entry.path().string(); + } + } + } + + return std::nullopt; +} + +} // 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 33acc1cde..e0ea0b670 100644 --- a/src/ros2_medkit_gateway/src/gateway_node.cpp +++ b/src/ros2_medkit_gateway/src/gateway_node.cpp @@ -61,6 +61,11 @@ GatewayNode::GatewayNode() : Node("ros2_medkit_gateway") { declare_parameter("manifest_path", ""); declare_parameter("manifest_strict_validation", true); + // Bulk data storage parameters + declare_parameter("bulk_data.storage_dir", "/tmp/ros2_medkit_bulk_data"); + declare_parameter("bulk_data.max_upload_size", 104857600); // 100MB + declare_parameter("bulk_data.categories", std::vector{}); + // Runtime (heuristic) discovery options // These control how nodes are mapped to SOVD entities in runtime mode declare_parameter("discovery.runtime.create_synthetic_components", true); @@ -244,6 +249,14 @@ GatewayNode::GatewayNode() : Node("ros2_medkit_gateway") { config_mgr_ = std::make_unique(this); fault_mgr_ = std::make_unique(this); + // Initialize bulk data store + auto bd_storage_dir = get_parameter("bulk_data.storage_dir").as_string(); + auto bd_max_upload = static_cast(get_parameter("bulk_data.max_upload_size").as_int()); + auto bd_categories = get_parameter("bulk_data.categories").as_string_array(); + bulk_data_store_ = std::make_unique(bd_storage_dir, bd_max_upload, bd_categories); + RCLCPP_INFO(get_logger(), "Bulk data store: dir=%s, max_upload=%zuB, categories=%zu", bd_storage_dir.c_str(), + bd_max_upload, bd_categories.size()); + // Connect topic sampler to discovery manager for component-topic mapping discovery_mgr_->set_topic_sampler(data_access_mgr_->get_native_sampler()); @@ -302,6 +315,10 @@ FaultManager * GatewayNode::get_fault_manager() const { return fault_mgr_.get(); } +BulkDataStore * GatewayNode::get_bulk_data_store() const { + return bulk_data_store_.get(); +} + void GatewayNode::refresh_cache() { RCLCPP_DEBUG(get_logger(), "Refreshing entity cache..."); diff --git a/src/ros2_medkit_gateway/src/http/handlers/bulkdata_handlers.cpp b/src/ros2_medkit_gateway/src/http/handlers/bulkdata_handlers.cpp index 2cde0010f..aa66eb433 100644 --- a/src/ros2_medkit_gateway/src/http/handlers/bulkdata_handlers.cpp +++ b/src/ros2_medkit_gateway/src/http/handlers/bulkdata_handlers.cpp @@ -16,9 +16,9 @@ #include #include -#include #include +#include "ros2_medkit_gateway/bulk_data_store.hpp" #include "ros2_medkit_gateway/gateway_node.hpp" #include "ros2_medkit_gateway/http/entity_path_utils.hpp" #include "ros2_medkit_gateway/http/error_codes.hpp" @@ -44,8 +44,24 @@ void BulkDataHandlers::handle_list_categories(const httplib::Request & req, http return; // Error response already sent } - // Currently only "rosbags" category is supported - nlohmann::json response = {{"items", nlohmann::json::array({"rosbags"})}}; + // Validate entity type supports bulk-data collection (SOVD Table 8) + if (auto err = HandlerContext::validate_collection_access(*entity_opt, ResourceCollection::BULK_DATA)) { + HandlerContext::send_error(res, httplib::StatusCode::BadRequest_400, ERR_COLLECTION_NOT_SUPPORTED, *err); + return; + } + + // Build categories list: "rosbags" always available + BulkDataStore categories + nlohmann::json categories = nlohmann::json::array(); + categories.push_back("rosbags"); // Always available via FaultManager + + auto * store = ctx_.bulk_data_store(); + if (store) { + for (const auto & cat : store->list_categories()) { + categories.push_back(cat); + } + } + + nlohmann::json response = {{"items", categories}}; HandlerContext::send_json(res, response); } @@ -65,6 +81,12 @@ void BulkDataHandlers::handle_list_descriptors(const httplib::Request & req, htt } auto entity = *entity_opt; + // Validate entity type supports bulk-data collection (SOVD Table 8) + if (auto err = HandlerContext::validate_collection_access(entity, ResourceCollection::BULK_DATA)) { + HandlerContext::send_error(res, httplib::StatusCode::BadRequest_400, ERR_COLLECTION_NOT_SUPPORTED, *err); + return; + } + // Extract and validate category from path auto category = extract_bulk_data_category(req.path); if (category.empty()) { @@ -72,70 +94,217 @@ void BulkDataHandlers::handle_list_descriptors(const httplib::Request & req, htt return; } - if (category != "rosbags") { - HandlerContext::send_error(res, httplib::StatusCode::NotFound_404, ERR_RESOURCE_NOT_FOUND, - "Unknown category: " + category); - return; - } + if (category == "rosbags") { + // === Rosbags: served via FaultManager === + // Get FaultManager from node + auto fault_mgr = ctx_.node()->get_fault_manager(); + + // Get all faults for this entity (filter by FQN/namespace path) + // Use the entity's FQN or namespace_path as the source_id filter + std::string source_filter = entity.fqn.empty() ? entity.namespace_path : entity.fqn; + auto faults_result = fault_mgr->list_faults(source_filter); + + // Build a map of fault_code -> fault_json for quick lookup + std::unordered_map fault_map; + if (faults_result.success && faults_result.data.contains("faults")) { + for (const auto & fault_json : faults_result.data["faults"]) { + if (fault_json.contains("fault_code")) { + std::string fc = fault_json["fault_code"].get(); + fault_map[fc] = fault_json; + } + } + } + + // Use batch rosbag retrieval (single service call) instead of N+1 individual calls + auto rosbags_result = fault_mgr->list_rosbags(source_filter); + + nlohmann::json items = nlohmann::json::array(); - // Get FaultManager from node - auto fault_mgr = ctx_.node()->get_fault_manager(); + if (rosbags_result.success && rosbags_result.data.contains("rosbags")) { + for (const auto & rosbag : rosbags_result.data["rosbags"]) { + std::string fault_code = rosbag.value("fault_code", ""); + std::string format = rosbag.value("format", "mcap"); + uint64_t size_bytes = rosbag.value("size_bytes", 0); + double duration_sec = rosbag.value("duration_sec", 0.0); - // Get all faults for this entity (filter by FQN/namespace path) - // Use the entity's FQN or namespace_path as the source_id filter - std::string source_filter = entity.fqn.empty() ? entity.namespace_path : entity.fqn; - auto faults_result = fault_mgr->list_faults(source_filter); + // Use fault_code as bulk_data_id + std::string bulk_data_id = fault_code; - // Build a map of fault_code -> fault_json for quick lookup - std::unordered_map fault_map; - if (faults_result.success && faults_result.data.contains("faults")) { - for (const auto & fault_json : faults_result.data["faults"]) { - if (fault_json.contains("fault_code")) { - std::string fc = fault_json["fault_code"].get(); - fault_map[fc] = fault_json; + // Get timestamp from fault if available + int64_t created_at_ns = 0; + auto it = fault_map.find(fault_code); + if (it != fault_map.end()) { + double first_occurred = it->second.value("first_occurred", 0.0); + created_at_ns = static_cast(first_occurred * 1'000'000'000); + } + + nlohmann::json descriptor = { + {"id", bulk_data_id}, + {"name", fault_code + " recording " + format_timestamp_ns(created_at_ns)}, + {"mimetype", get_rosbag_mimetype(format)}, + {"size", size_bytes}, + {"creation_date", format_timestamp_ns(created_at_ns)}, + {"x-medkit", {{"fault_code", fault_code}, {"duration_sec", duration_sec}, {"format", format}}}}; + items.push_back(descriptor); } } + + nlohmann::json response = {{"items", items}}; + HandlerContext::send_json(res, response); + } else { + // === Non-rosbag categories: served via BulkDataStore === + auto * store = ctx_.bulk_data_store(); + if (!store || !store->is_known_category(category)) { + HandlerContext::send_error(res, httplib::StatusCode::NotFound_404, ERR_RESOURCE_NOT_FOUND, + "Unknown category: " + category); + return; + } + + auto items_list = store->list_items(entity_info->entity_id, category); + nlohmann::json json_items = nlohmann::json::array(); + for (const auto & item : items_list) { + nlohmann::json desc = { + {"id", item.id}, + {"name", item.name}, + {"mimetype", item.mime_type}, + {"size", item.size}, + {"creation_date", item.created}, + }; + if (!item.description.empty()) { + desc["description"] = item.description; + } + if (!item.metadata.empty()) { + desc["x-medkit"] = item.metadata; + } + json_items.push_back(desc); + } + nlohmann::json response = {{"items", json_items}}; + HandlerContext::send_json(res, response); } +} - // Use batch rosbag retrieval (single service call) instead of N+1 individual calls - auto rosbags_result = fault_mgr->list_rosbags(source_filter); +void BulkDataHandlers::handle_upload(const httplib::Request & req, httplib::Response & res) { + // Parse entity path from request URL + auto entity_info = parse_entity_path(req.path); + if (!entity_info) { + HandlerContext::send_error(res, httplib::StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid entity path"); + return; + } - nlohmann::json items = nlohmann::json::array(); + // Validate entity exists and matches the route type + auto entity_opt = ctx_.validate_entity_for_route(req, res, entity_info->entity_id); + if (!entity_opt) { + return; // Error response already sent + } + + // Validate entity type supports bulk-data collection (SOVD Table 8) + if (auto err = HandlerContext::validate_collection_access(*entity_opt, ResourceCollection::BULK_DATA)) { + HandlerContext::send_error(res, httplib::StatusCode::BadRequest_400, ERR_COLLECTION_NOT_SUPPORTED, *err); + return; + } - if (rosbags_result.success && rosbags_result.data.contains("rosbags")) { - for (const auto & rosbag : rosbags_result.data["rosbags"]) { - std::string fault_code = rosbag.value("fault_code", ""); - std::string format = rosbag.value("format", "mcap"); - uint64_t size_bytes = rosbag.value("size_bytes", 0); - double duration_sec = rosbag.value("duration_sec", 0.0); + // Extract and validate category from path + auto category = extract_bulk_data_category(req.path); + if (category.empty()) { + HandlerContext::send_error(res, httplib::StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Missing category"); + return; + } - // Use fault_code as bulk_data_id - std::string bulk_data_id = fault_code; + // Rosbags are managed by the fault system, not user-uploadable + if (category == "rosbags") { + HandlerContext::send_error(res, httplib::StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, + "Category 'rosbags' does not support upload. " + "Rosbags are managed by the fault system."); + return; + } - // Get timestamp from fault if available - int64_t created_at_ns = 0; - auto it = fault_map.find(fault_code); - if (it != fault_map.end()) { - double first_occurred = it->second.value("first_occurred", 0.0); - created_at_ns = static_cast(first_occurred * 1'000'000'000); - } + // Check BulkDataStore is available + auto * store = ctx_.bulk_data_store(); + if (store == nullptr) { + HandlerContext::send_error(res, httplib::StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, + "Bulk data storage not configured"); + return; + } - nlohmann::json descriptor = { - {"id", bulk_data_id}, - {"name", fault_code + " recording " + format_timestamp_ns(created_at_ns)}, - {"mimetype", get_rosbag_mimetype(format)}, - {"size", size_bytes}, - {"creation_date", format_timestamp_ns(created_at_ns)}, - {"x-medkit", {{"fault_code", fault_code}, {"duration_sec", duration_sec}, {"format", format}}}}; - items.push_back(descriptor); + // Validate category is known + if (!store->is_known_category(category)) { + HandlerContext::send_error(res, httplib::StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, + "Unknown bulk-data category: " + category); + return; + } + + // Extract multipart file + if (!req.has_file("file")) { + HandlerContext::send_error(res, httplib::StatusCode::BadRequest_400, ERR_INVALID_REQUEST, + "Missing 'file' field in multipart/form-data request"); + return; + } + + const auto & file = req.get_file_value("file"); + std::string filename = file.filename.empty() ? "upload" : file.filename; + std::string content_type = file.content_type.empty() ? "application/octet-stream" : file.content_type; + + // Check file size against limit + if (store->max_upload_bytes() > 0 && file.content.size() > store->max_upload_bytes()) { + HandlerContext::send_error(res, static_cast(413), ERR_PAYLOAD_TOO_LARGE, + "File size exceeds maximum upload limit"); + return; + } + + // Extract optional description and metadata + std::string description; + if (req.has_file("description")) { + description = req.get_file_value("description").content; + } + + nlohmann::json metadata = nlohmann::json::object(); + if (req.has_file("metadata")) { + const auto & meta_str = req.get_file_value("metadata").content; + if (!meta_str.empty()) { + auto parsed = nlohmann::json::parse(meta_str, nullptr, false); + if (parsed.is_discarded()) { + HandlerContext::send_error(res, httplib::StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, + "Invalid JSON in 'metadata' field"); + return; + } + if (!parsed.is_object()) { + HandlerContext::send_error(res, httplib::StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, + "metadata must be a JSON object"); + return; + } + metadata = std::move(parsed); } } - nlohmann::json response = {{"items", items}}; - HandlerContext::send_json(res, response); + // Store the file + auto result = + store->store(entity_info->entity_id, category, filename, content_type, file.content, description, metadata); + if (!result) { + HandlerContext::send_error(res, httplib::StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, result.error()); + return; + } + + // Build response JSON + const auto & desc = *result; + nlohmann::json descriptor_json = {{"id", desc.id}, + {"name", desc.name}, + {"mimetype", desc.mime_type}, + {"size", desc.size}, + {"creation_date", desc.created}}; + if (!desc.description.empty()) { + descriptor_json["description"] = desc.description; + } + if (!desc.metadata.empty()) { + descriptor_json["x-medkit"] = desc.metadata; + } + + // Return 201 Created with Location header + res.status = 201; + res.set_header("Location", req.path + "/" + desc.id); + HandlerContext::send_json(res, descriptor_json); } -void BulkDataHandlers::handle_download(const httplib::Request & req, httplib::Response & res) { +void BulkDataHandlers::handle_delete(const httplib::Request & req, httplib::Response & res) { // Parse entity path from request URL auto entity_info = parse_entity_path(req.path); if (!entity_info) { @@ -148,60 +317,169 @@ void BulkDataHandlers::handle_download(const httplib::Request & req, httplib::Re if (!entity_opt) { return; // Error response already sent } - auto entity = *entity_opt; - // Extract category and bulk_data_id from path + // Validate entity type supports bulk-data collection (SOVD Table 8) + if (auto err = HandlerContext::validate_collection_access(*entity_opt, ResourceCollection::BULK_DATA)) { + HandlerContext::send_error(res, httplib::StatusCode::BadRequest_400, ERR_COLLECTION_NOT_SUPPORTED, *err); + return; + } + + // Extract and validate category from path auto category = extract_bulk_data_category(req.path); - auto bulk_data_id = extract_bulk_data_id(req.path); + if (category.empty()) { + HandlerContext::send_error(res, httplib::StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Missing category"); + return; + } - if (category != "rosbags") { - HandlerContext::send_error(res, httplib::StatusCode::NotFound_404, ERR_RESOURCE_NOT_FOUND, - "Unknown category: " + category); + // Rosbags are managed by the fault system, not user-deletable + if (category == "rosbags") { + HandlerContext::send_error(res, httplib::StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, + "Category 'rosbags' does not support deletion. " + "Rosbags are managed by the fault system."); return; } - if (bulk_data_id.empty()) { + // Extract item ID + auto item_id = extract_bulk_data_id(req.path); + if (item_id.empty()) { HandlerContext::send_error(res, httplib::StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Missing bulk-data ID"); return; } - // Get FaultManager from node - auto fault_mgr = ctx_.node()->get_fault_manager(); + // Check BulkDataStore is available + auto * store = ctx_.bulk_data_store(); + if (store == nullptr) { + HandlerContext::send_error(res, httplib::StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, + "Bulk data storage not configured"); + return; + } - // bulk_data_id is the fault_code - std::string fault_code = bulk_data_id; + // Validate category is known + if (!store->is_known_category(category)) { + HandlerContext::send_error(res, httplib::StatusCode::BadRequest_400, ERR_INVALID_PARAMETER, + "Unknown bulk-data category: " + category); + return; + } - // Get rosbag info - auto rosbag_result = fault_mgr->get_rosbag(fault_code); - if (!rosbag_result.success || !rosbag_result.data.contains("file_path")) { - HandlerContext::send_error(res, httplib::StatusCode::NotFound_404, ERR_RESOURCE_NOT_FOUND, "Bulk-data not found", - {{"bulk_data_id", bulk_data_id}}); + // Delete the item + auto result = store->remove(entity_info->entity_id, category, item_id); + if (!result) { + HandlerContext::send_error(res, httplib::StatusCode::NotFound_404, ERR_RESOURCE_NOT_FOUND, + "Bulk-data item not found"); return; } - // Security check: verify rosbag belongs to this entity - // Use targeted get_fault lookup instead of loading the entire fault list - std::string source_filter = entity.fqn.empty() ? entity.namespace_path : entity.fqn; - auto fault_result = fault_mgr->get_fault(fault_code, source_filter); + // Return 204 No Content + res.status = 204; +} - if (!fault_result.success) { - HandlerContext::send_error(res, httplib::StatusCode::NotFound_404, ERR_RESOURCE_NOT_FOUND, - "Bulk-data not found for this entity", {{"entity_id", entity_info->entity_id}}); +void BulkDataHandlers::handle_download(const httplib::Request & req, httplib::Response & res) { + // Parse entity path from request URL + auto entity_info = parse_entity_path(req.path); + if (!entity_info) { + HandlerContext::send_error(res, httplib::StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Invalid entity path"); + return; + } + + // Validate entity exists and matches the route type + auto entity_opt = ctx_.validate_entity_for_route(req, res, entity_info->entity_id); + if (!entity_opt) { + return; // Error response already sent + } + auto entity = *entity_opt; + + // Validate entity type supports bulk-data collection (SOVD Table 8) + if (auto err = HandlerContext::validate_collection_access(entity, ResourceCollection::BULK_DATA)) { + HandlerContext::send_error(res, httplib::StatusCode::BadRequest_400, ERR_COLLECTION_NOT_SUPPORTED, *err); + return; + } + + // Extract category and bulk_data_id from path + auto category = extract_bulk_data_category(req.path); + auto bulk_data_id = extract_bulk_data_id(req.path); + + if (bulk_data_id.empty()) { + HandlerContext::send_error(res, httplib::StatusCode::BadRequest_400, ERR_INVALID_REQUEST, "Missing bulk-data ID"); return; } - // Get file path and stream the file - std::string file_path = rosbag_result.data["file_path"].get(); - std::string format = rosbag_result.data.value("format", "mcap"); - auto mimetype = get_rosbag_mimetype(format); - std::string filename = fault_code + "." + format; + if (category == "rosbags") { + // === Rosbags: served via FaultManager === + // Get FaultManager from node + auto fault_mgr = ctx_.node()->get_fault_manager(); - // Set response headers for file download - res.set_header("Content-Disposition", "attachment; filename=\"" + filename + "\""); + // bulk_data_id is the fault_code + std::string fault_code = bulk_data_id; - if (!stream_file_to_response(res, file_path, mimetype)) { - HandlerContext::send_error(res, httplib::StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, - "Failed to read rosbag file"); + // Get rosbag info + auto rosbag_result = fault_mgr->get_rosbag(fault_code); + if (!rosbag_result.success || !rosbag_result.data.contains("file_path")) { + HandlerContext::send_error(res, httplib::StatusCode::NotFound_404, ERR_RESOURCE_NOT_FOUND, "Bulk-data not found", + {{"bulk_data_id", bulk_data_id}}); + return; + } + + // Security check: verify rosbag belongs to this entity + // Use targeted get_fault lookup instead of loading the entire fault list + std::string source_filter = entity.fqn.empty() ? entity.namespace_path : entity.fqn; + auto fault_result = fault_mgr->get_fault(fault_code, source_filter); + + if (!fault_result.success) { + HandlerContext::send_error(res, httplib::StatusCode::NotFound_404, ERR_RESOURCE_NOT_FOUND, + "Bulk-data not found for this entity", {{"entity_id", entity_info->entity_id}}); + return; + } + + // Get file path and stream the file + std::string file_path = rosbag_result.data["file_path"].get(); + std::string format = rosbag_result.data.value("format", "mcap"); + auto mimetype = get_rosbag_mimetype(format); + std::string filename = fault_code + "." + format; + + // Sanitize quotes in filename for Content-Disposition header safety + std::string safe_name = filename; + std::replace(safe_name.begin(), safe_name.end(), '"', '_'); + + // Set response headers for file download + res.set_header("Content-Disposition", "attachment; filename=\"" + safe_name + "\""); + + if (!stream_file_to_response(res, file_path, mimetype)) { + HandlerContext::send_error(res, httplib::StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, + "Failed to read rosbag file"); + } + } else { + // === Non-rosbag categories: served via BulkDataStore === + auto * store = ctx_.bulk_data_store(); + if (!store || !store->is_known_category(category)) { + HandlerContext::send_error(res, httplib::StatusCode::NotFound_404, ERR_RESOURCE_NOT_FOUND, + "Unknown category: " + category); + return; + } + + auto file_path = store->get_file_path(entity_info->entity_id, category, bulk_data_id); + if (!file_path) { + HandlerContext::send_error(res, httplib::StatusCode::NotFound_404, ERR_RESOURCE_NOT_FOUND, "Bulk-data not found", + {{"bulk_data_id", bulk_data_id}}); + return; + } + + // Get descriptor for filename and MIME type + auto item = store->get_item(entity_info->entity_id, category, bulk_data_id); + std::string filename = item ? item->name : bulk_data_id; + std::string mimetype = item ? item->mime_type : "application/octet-stream"; + + // Sanitize quotes in filename for Content-Disposition header safety + std::string safe_name = filename; + std::replace(safe_name.begin(), safe_name.end(), '"', '_'); + + // Content-Disposition with original filename + res.set_header("Content-Disposition", "attachment; filename=\"" + safe_name + "\""); + + // Use generic stream utility (from subtask 1) + if (!ros2_medkit_gateway::stream_file_to_response(res, *file_path, mimetype)) { + HandlerContext::send_error(res, httplib::StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, + "Failed to read file"); + } } } @@ -213,47 +491,8 @@ bool BulkDataHandlers::stream_file_to_response(httplib::Response & res, const st return false; } - // Get file size without reading entire file into memory - std::error_code ec; - auto file_size = std::filesystem::file_size(actual_path, ec); - if (ec) { - return false; - } - - // Use chunked streaming via content provider to avoid loading large rosbag files into memory. - // Rosbag files can be hundreds of MB to multiple GB. - static constexpr size_t kChunkSize = 64 * 1024; // 64 KB chunks - - res.set_content_provider(static_cast(file_size), content_type, - [actual_path](size_t offset, size_t length, httplib::DataSink & sink) -> bool { - std::ifstream file(actual_path, std::ios::binary); - if (!file.is_open()) { - return false; - } - - file.seekg(static_cast(offset)); - if (!file.good()) { - return false; - } - - size_t remaining = length; - std::vector buf(std::min(remaining, kChunkSize)); - - while (remaining > 0 && file.good()) { - size_t to_read = std::min(remaining, kChunkSize); - file.read(buf.data(), static_cast(to_read)); - auto bytes_read = static_cast(file.gcount()); - if (bytes_read == 0) { - break; - } - sink.write(buf.data(), bytes_read); - remaining -= bytes_read; - } - - return remaining == 0; - }); - - return true; + // Delegate to the generic stream utility + return ros2_medkit_gateway::stream_file_to_response(res, actual_path, content_type); } std::string BulkDataHandlers::resolve_rosbag_file_path(const std::string & path) { diff --git a/src/ros2_medkit_gateway/src/http/rest_server.cpp b/src/ros2_medkit_gateway/src/http/rest_server.cpp index 7bf73dc54..6d98de4dd 100644 --- a/src/ros2_medkit_gateway/src/http/rest_server.cpp +++ b/src/ros2_medkit_gateway/src/http/rest_server.cpp @@ -37,6 +37,16 @@ RESTServer::RESTServer(GatewayNode * node, const std::string & host, int port, c // Create HTTP/HTTPS server manager http_server_ = std::make_unique(tls_config_); + // Set maximum payload size for uploads (cpp-httplib default is 8MB) + auto * srv = http_server_->get_server(); + if (srv) { + size_t max_payload = node_->get_bulk_data_store() ? node_->get_bulk_data_store()->max_upload_bytes() : 0; + if (max_payload > 0) { + srv->set_payload_max_length(max_payload); + RCLCPP_INFO(rclcpp::get_logger("rest_server"), "Max payload length set to %zu bytes", max_payload); + } + } + // Initialize auth manager and middleware if auth is enabled if (auth_config_.enabled) { auth_manager_ = std::make_unique(auth_config_); @@ -49,8 +59,8 @@ RESTServer::RESTServer(GatewayNode * node, const std::string & host, int port, c } // Create handler context and domain-specific handlers - handler_ctx_ = - std::make_unique(node_, cors_config_, auth_config_, tls_config_, auth_manager_.get()); + handler_ctx_ = std::make_unique(node_, cors_config_, auth_config_, tls_config_, + auth_manager_.get(), node_->get_bulk_data_store()); health_handlers_ = std::make_unique(*handler_ctx_); discovery_handlers_ = std::make_unique(*handler_ctx_); @@ -800,6 +810,40 @@ void RESTServer::setup_routes() { bulkdata_handlers_->handle_download(req, res); }); + // Upload bulk-data (POST) β€” apps and components only (REQ_INTEROP_074) + srv->Post((api_path("/apps") + R"(/([^/]+)/bulk-data/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + bulkdata_handlers_->handle_upload(req, res); + }); + srv->Post((api_path("/components") + R"(/([^/]+)/bulk-data/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + bulkdata_handlers_->handle_upload(req, res); + }); + // Bulk data upload not supported for areas and functions (405) + auto bulk_upload_405 = [this](const httplib::Request & /*req*/, httplib::Response & res) { + handlers::HandlerContext::send_error(res, httplib::StatusCode::MethodNotAllowed_405, ERR_INVALID_REQUEST, + "Bulk data upload is only supported for components and apps"); + }; + srv->Post((api_path("/areas") + R"(/([^/]+)/bulk-data/([^/]+)$)"), bulk_upload_405); + srv->Post((api_path("/functions") + R"(/([^/]+)/bulk-data/([^/]+)$)"), bulk_upload_405); + + // Delete bulk-data (DELETE) β€” apps and components only (REQ_INTEROP_074) + srv->Delete((api_path("/apps") + R"(/([^/]+)/bulk-data/([^/]+)/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + bulkdata_handlers_->handle_delete(req, res); + }); + srv->Delete((api_path("/components") + R"(/([^/]+)/bulk-data/([^/]+)/([^/]+)$)"), + [this](const httplib::Request & req, httplib::Response & res) { + bulkdata_handlers_->handle_delete(req, res); + }); + // Bulk data deletion not supported for areas and functions (405) + auto bulk_delete_405 = [this](const httplib::Request & /*req*/, httplib::Response & res) { + handlers::HandlerContext::send_error(res, httplib::StatusCode::MethodNotAllowed_405, ERR_INVALID_REQUEST, + "Bulk data deletion is only supported for components and apps"); + }; + srv->Delete((api_path("/areas") + R"(/([^/]+)/bulk-data/([^/]+)/([^/]+)$)"), bulk_delete_405); + srv->Delete((api_path("/functions") + R"(/([^/]+)/bulk-data/([^/]+)/([^/]+)$)"), bulk_delete_405); + // Nested entities - subareas srv->Get((api_path("/areas") + R"(/([^/]+)/subareas/([^/]+)/bulk-data$)"), [this](const httplib::Request & req, httplib::Response & res) { diff --git a/src/ros2_medkit_gateway/test/test_bulk_data_store.cpp b/src/ros2_medkit_gateway/test/test_bulk_data_store.cpp new file mode 100644 index 000000000..6de1f6d79 --- /dev/null +++ b/src/ros2_medkit_gateway/test/test_bulk_data_store.cpp @@ -0,0 +1,375 @@ +// 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/bulk_data_store.hpp" + +#include + +#include +#include +#include +#include + +namespace ros2_medkit_gateway { +namespace { + +class BulkDataStoreTest : public ::testing::Test { + protected: + void SetUp() override { + // Create unique temp directory for each test + test_dir_ = std::filesystem::temp_directory_path() / + ("bulk_data_test_" + std::to_string(getpid()) + "_" + std::to_string(test_counter_++)); + std::filesystem::create_directories(test_dir_); + } + + void TearDown() override { + std::error_code ec; + std::filesystem::remove_all(test_dir_, ec); + } + + std::filesystem::path test_dir_; + static int test_counter_; +}; + +int BulkDataStoreTest::test_counter_ = 0; + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, StoreAndRetrieve) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); + + auto result = store.store("my_app", "calibration", "test.bin", "application/octet-stream", "hello world"); + ASSERT_TRUE(result.has_value()) << result.error(); + + auto desc = result.value(); + EXPECT_FALSE(desc.id.empty()); + EXPECT_EQ(desc.category, "calibration"); + EXPECT_EQ(desc.name, "test.bin"); + EXPECT_EQ(desc.mime_type, "application/octet-stream"); + EXPECT_EQ(desc.size, 11u); + EXPECT_FALSE(desc.created.empty()); + + // Retrieve + auto item = store.get_item("my_app", "calibration", desc.id); + ASSERT_TRUE(item.has_value()); + EXPECT_EQ(item->id, desc.id); + EXPECT_EQ(item->name, "test.bin"); + EXPECT_EQ(item->size, 11u); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, StoreCreatesDirectoryStructure) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); + + auto result = store.store("entity_1", "calibration", "data.bin", "application/octet-stream", "payload"); + ASSERT_TRUE(result.has_value()); + + auto dir = test_dir_ / "entity_1" / "calibration" / result->id; + EXPECT_TRUE(std::filesystem::is_directory(dir)); + EXPECT_TRUE(std::filesystem::is_regular_file(dir / "descriptor.json")); + EXPECT_TRUE(std::filesystem::is_regular_file(dir / "data.bin")); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, StoreWithMetadata) { + BulkDataStore store(test_dir_.string(), 0, {"firmware"}); + + nlohmann::json meta = {{"version", "2.1.0"}, {"board", "rev3"}}; + auto result = store.store("ecu", "firmware", "fw.bin", "application/octet-stream", "firmware_data", + "Firmware update v2.1", meta); + ASSERT_TRUE(result.has_value()); + + EXPECT_EQ(result->description, "Firmware update v2.1"); + EXPECT_EQ(result->metadata["version"], "2.1.0"); + EXPECT_EQ(result->metadata["board"], "rev3"); + + // Verify it persists + auto item = store.get_item("ecu", "firmware", result->id); + ASSERT_TRUE(item.has_value()); + EXPECT_EQ(item->description, "Firmware update v2.1"); + EXPECT_EQ(item->metadata["version"], "2.1.0"); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, ListItemsInCategory) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); + + ASSERT_TRUE(store.store("app1", "calibration", "a.bin", "application/octet-stream", "aaa").has_value()); + ASSERT_TRUE(store.store("app1", "calibration", "b.bin", "application/octet-stream", "bbb").has_value()); + ASSERT_TRUE(store.store("app1", "calibration", "c.bin", "application/octet-stream", "ccc").has_value()); + + auto items = store.list_items("app1", "calibration"); + EXPECT_EQ(items.size(), 3u); + + // Verify all items have distinct IDs + std::set ids; + for (const auto & item : items) { + ids.insert(item.id); + } + EXPECT_EQ(ids.size(), 3u); +} + +// @verifies REQ_INTEROP_071 +TEST_F(BulkDataStoreTest, ListCategories) { + BulkDataStore store(test_dir_.string(), 0, {"calibration", "firmware", "comlogs"}); + + auto cats = store.list_categories(); + EXPECT_EQ(cats.size(), 3u); + + std::set cat_set(cats.begin(), cats.end()); + EXPECT_TRUE(cat_set.count("calibration") > 0); + EXPECT_TRUE(cat_set.count("firmware") > 0); + EXPECT_TRUE(cat_set.count("comlogs") > 0); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, RemoveItem) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); + + auto result = store.store("app1", "calibration", "data.bin", "application/octet-stream", "payload"); + ASSERT_TRUE(result.has_value()); + auto id = result->id; + + // Verify exists + EXPECT_TRUE(store.get_item("app1", "calibration", id).has_value()); + + // Remove + auto remove_result = store.remove("app1", "calibration", id); + ASSERT_TRUE(remove_result.has_value()); + + // Verify gone + EXPECT_FALSE(store.get_item("app1", "calibration", id).has_value()); + + // Directory should be removed + auto dir = test_dir_ / "app1" / "calibration" / id; + EXPECT_FALSE(std::filesystem::exists(dir)); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, RemoveNonexistent) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); + + auto result = store.remove("app1", "calibration", "nonexistent_id"); + EXPECT_FALSE(result.has_value()); + EXPECT_TRUE(result.error().find("not found") != std::string::npos); +} + +// @verifies REQ_INTEROP_073 +TEST_F(BulkDataStoreTest, GetFilePath) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); + + auto result = store.store("app1", "calibration", "test.bin", "application/octet-stream", "hello world"); + ASSERT_TRUE(result.has_value()); + + auto path = store.get_file_path("app1", "calibration", result->id); + ASSERT_TRUE(path.has_value()); + EXPECT_TRUE(std::filesystem::is_regular_file(*path)); + + // Verify content + std::ifstream ifs(*path, std::ios::binary); + std::string content((std::istreambuf_iterator(ifs)), std::istreambuf_iterator()); + EXPECT_EQ(content, "hello world"); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, GenerateUniqueIds) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); + + std::set ids; + for (int i = 0; i < 100; ++i) { + auto result = store.store("app1", "calibration", "file.bin", "application/octet-stream", "x"); + ASSERT_TRUE(result.has_value()) << "Failed at iteration " << i << ": " << result.error(); + ids.insert(result->id); + } + EXPECT_EQ(ids.size(), 100u); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, MaxUploadSizeEnforced) { + BulkDataStore store(test_dir_.string(), 100, {"calibration"}); // 100 bytes max + + // Should succeed (50 bytes) + auto small = store.store("app1", "calibration", "small.bin", "application/octet-stream", std::string(50, 'x')); + EXPECT_TRUE(small.has_value()); + + // Should fail (200 bytes) + auto large = store.store("app1", "calibration", "large.bin", "application/octet-stream", std::string(200, 'x')); + EXPECT_FALSE(large.has_value()); + EXPECT_TRUE(large.error().find("exceeds maximum") != std::string::npos); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, UnknownCategory) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); + + EXPECT_TRUE(store.is_known_category("calibration")); + EXPECT_FALSE(store.is_known_category("bogus")); + EXPECT_FALSE(store.is_known_category("rosbags")); // rosbags not managed by BulkDataStore +} + +// @verifies REQ_INTEROP_071 +TEST_F(BulkDataStoreTest, EmptyCategories) { + BulkDataStore store(test_dir_.string(), 0); + + auto cats = store.list_categories(); + EXPECT_TRUE(cats.empty()); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, PathTraversalRejected) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); + + // entity_id with path traversal + auto result1 = store.store("../etc", "calibration", "evil.bin", "application/octet-stream", "data"); + EXPECT_FALSE(result1.has_value()); + EXPECT_TRUE(result1.error().find("'..'") != std::string::npos); + + // entity_id with slash + auto result2 = store.store("a/b", "calibration", "evil.bin", "application/octet-stream", "data"); + EXPECT_FALSE(result2.has_value()); + EXPECT_TRUE(result2.error().find("path separator") != std::string::npos); + + // category with traversal + auto result3 = store.store("app1", "../secret", "evil.bin", "application/octet-stream", "data"); + EXPECT_FALSE(result3.has_value()); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, StoreAtomicWriteDescriptorExists) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); + + auto result = store.store("app1", "calibration", "data.bin", "application/octet-stream", "payload"); + ASSERT_TRUE(result.has_value()); + + auto dir = test_dir_ / "app1" / "calibration" / result->id; + EXPECT_TRUE(std::filesystem::is_regular_file(dir / "descriptor.json")); + + // No orphan temp files + EXPECT_FALSE(std::filesystem::exists(dir / ".data.tmp")); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, StoreUnknownCategoryRejected) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); + + auto result = store.store("app1", "bogus", "data.bin", "application/octet-stream", "payload"); + EXPECT_FALSE(result.has_value()); + EXPECT_TRUE(result.error().find("Unknown category") != std::string::npos); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, ListItemsEmptyCategory) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); + + auto items = store.list_items("app1", "calibration"); + EXPECT_TRUE(items.empty()); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, ListItemsWrongEntity) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); + + ASSERT_TRUE(store.store("app1", "calibration", "data.bin", "application/octet-stream", "payload").has_value()); + + auto items = store.list_items("app2", "calibration"); + EXPECT_TRUE(items.empty()); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, StoreEmptyFile) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); + + auto result = store.store("app1", "calibration", "empty.bin", "application/octet-stream", ""); + ASSERT_TRUE(result.has_value()); + EXPECT_EQ(result->size, 0u); + + auto item = store.get_item("app1", "calibration", result->id); + ASSERT_TRUE(item.has_value()); + EXPECT_EQ(item->size, 0u); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, StoreEmptyFilename) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); + + auto result = store.store("app1", "calibration", "", "application/octet-stream", "data"); + ASSERT_TRUE(result.has_value()); + EXPECT_EQ(result->name, "upload"); // Default filename +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, RemoveThenListDoesNotInclude) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); + + auto r1 = store.store("app1", "calibration", "a.bin", "application/octet-stream", "aaa"); + auto r2 = store.store("app1", "calibration", "b.bin", "application/octet-stream", "bbb"); + ASSERT_TRUE(r1.has_value()); + ASSERT_TRUE(r2.has_value()); + + ASSERT_TRUE(store.remove("app1", "calibration", r1->id).has_value()); + + auto items = store.list_items("app1", "calibration"); + EXPECT_EQ(items.size(), 1u); + EXPECT_EQ(items[0].id, r2->id); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, IdFormatIsReadable) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); + + auto result = store.store("app1", "calibration", "data.bin", "application/octet-stream", "x"); + ASSERT_TRUE(result.has_value()); + + // ID should start with category name + EXPECT_TRUE(result->id.rfind("calibration_", 0) == 0) << "ID: " << result->id; + // ID should contain underscore-separated parts + EXPECT_GT(result->id.size(), std::string("calibration_").size()); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, GetFilePathNonexistent) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); + + auto path = store.get_file_path("app1", "calibration", "nonexistent"); + EXPECT_FALSE(path.has_value()); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, MaxUploadZeroMeansUnlimited) { + BulkDataStore store(test_dir_.string(), 0, {"calibration"}); // 0 = unlimited + + auto result = store.store("app1", "calibration", "big.bin", "application/octet-stream", std::string(10000, 'x')); + EXPECT_TRUE(result.has_value()); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataStoreTest, StoreLargeFile) { + BulkDataStore store(test_dir_.string(), 10 * 1024 * 1024, {"calibration"}); + + // 5MB payload + std::string payload(5 * 1024 * 1024, 'A'); + auto result = store.store("app1", "calibration", "large.bin", "application/octet-stream", payload); + ASSERT_TRUE(result.has_value()); + EXPECT_EQ(result->size, payload.size()); + + // Verify file contents match + auto path = store.get_file_path("app1", "calibration", result->id); + ASSERT_TRUE(path.has_value()); + std::ifstream f(*path, std::ios::binary); + ASSERT_TRUE(f.good()); + std::string read_back((std::istreambuf_iterator(f)), std::istreambuf_iterator()); + EXPECT_EQ(read_back, payload); +} + +} // namespace +} // namespace ros2_medkit_gateway diff --git a/src/ros2_medkit_gateway/test/test_bulkdata_handlers.cpp b/src/ros2_medkit_gateway/test/test_bulkdata_handlers.cpp index a5841e2a1..01d491789 100644 --- a/src/ros2_medkit_gateway/test/test_bulkdata_handlers.cpp +++ b/src/ros2_medkit_gateway/test/test_bulkdata_handlers.cpp @@ -14,6 +14,10 @@ #include +#include + +#include "ros2_medkit_gateway/bulk_data_store.hpp" +#include "ros2_medkit_gateway/http/error_codes.hpp" #include "ros2_medkit_gateway/http/handlers/bulkdata_handlers.hpp" #include "ros2_medkit_gateway/http/http_utils.hpp" @@ -94,3 +98,94 @@ TEST_F(BulkDataHandlersTest, FormatTimestampNsNegativeFallback) { EXPECT_FALSE(result.empty()); EXPECT_TRUE(result.find("Z") != std::string::npos); } + +// === Descriptor to JSON conversion tests === + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataHandlersTest, DescriptorToJsonConversion) { + ros2_medkit_gateway::BulkDataStore::ItemDescriptor desc; + desc.id = "calibration_123_abcd1234"; + desc.name = "test.bin"; + desc.mime_type = "application/octet-stream"; + desc.size = 1024; + desc.created = "2026-01-01T00:00:00.000Z"; + desc.description = "Test upload"; + desc.metadata = nlohmann::json::object(); + + nlohmann::json j = {{"id", desc.id}, + {"name", desc.name}, + {"mimetype", desc.mime_type}, + {"size", desc.size}, + {"creation_date", desc.created}, + {"description", desc.description}}; + + EXPECT_EQ(j["id"], "calibration_123_abcd1234"); + EXPECT_EQ(j["name"], "test.bin"); + EXPECT_EQ(j["mimetype"], "application/octet-stream"); + EXPECT_EQ(j["size"], 1024); + EXPECT_EQ(j["creation_date"], "2026-01-01T00:00:00.000Z"); + EXPECT_EQ(j["description"], "Test upload"); + EXPECT_FALSE(j.contains("x-medkit")); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataHandlersTest, DescriptorToJsonWithMetadata) { + ros2_medkit_gateway::BulkDataStore::ItemDescriptor desc; + desc.id = "calibration_123_abcd1234"; + desc.name = "cal.bin"; + desc.mime_type = "application/octet-stream"; + desc.size = 512; + desc.created = "2026-01-01T00:00:00.000Z"; + desc.description = ""; + desc.metadata = {{"sensor", "lidar"}, {"version", 2}}; + + nlohmann::json j = {{"id", desc.id}, + {"name", desc.name}, + {"mimetype", desc.mime_type}, + {"size", desc.size}, + {"creation_date", desc.created}, + {"description", desc.description}}; + if (!desc.metadata.empty()) { + j["x-medkit"] = desc.metadata; + } + + EXPECT_TRUE(j.contains("x-medkit")); + EXPECT_EQ(j["x-medkit"]["sensor"], "lidar"); + EXPECT_EQ(j["x-medkit"]["version"], 2); +} + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataHandlersTest, DescriptorToJsonWithoutDescription) { + ros2_medkit_gateway::BulkDataStore::ItemDescriptor desc; + desc.id = "firmware_456_ef012345"; + desc.name = "fw.img"; + desc.mime_type = "application/octet-stream"; + desc.size = 2048; + desc.created = "2026-06-15T12:00:00.000Z"; + desc.description = ""; + desc.metadata = nlohmann::json::object(); + + nlohmann::json j = {{"id", desc.id}, + {"name", desc.name}, + {"mimetype", desc.mime_type}, + {"size", desc.size}, + {"creation_date", desc.created}}; + // Only add description if non-empty (matching handler pattern) + if (!desc.description.empty()) { + j["description"] = desc.description; + } + if (!desc.metadata.empty()) { + j["x-medkit"] = desc.metadata; + } + + EXPECT_FALSE(j.contains("description")); + EXPECT_FALSE(j.contains("x-medkit")); +} + +// === Error code tests === + +// @verifies REQ_INTEROP_074 +TEST_F(BulkDataHandlersTest, PayloadTooLargeErrorCodeDefined) { + EXPECT_NE(ros2_medkit_gateway::ERR_PAYLOAD_TOO_LARGE, nullptr); + EXPECT_STREQ(ros2_medkit_gateway::ERR_PAYLOAD_TOO_LARGE, "payload-too-large"); +} diff --git a/src/ros2_medkit_gateway/test/test_bulkdata_upload.test.py b/src/ros2_medkit_gateway/test/test_bulkdata_upload.test.py new file mode 100644 index 000000000..037511533 --- /dev/null +++ b/src/ros2_medkit_gateway/test/test_bulkdata_upload.test.py @@ -0,0 +1,460 @@ +#!/usr/bin/env python3 +# Copyright 2026 bburda +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +""" +Integration tests for bulk data upload (POST) and delete (DELETE) endpoints. + +Launches the gateway node with bulk_data categories configured, then tests +the full CRUD lifecycle: upload, list, download, delete. +""" + +import json +import os +import tempfile +import time +import unittest + +from launch import LaunchDescription +from launch.actions import TimerAction +import launch_ros.actions +import launch_testing.actions +import requests + + +# Use a unique port to avoid conflicts with other integration tests +TEST_PORT = 8765 + + +def get_coverage_env(): + """Get environment variables for gcov coverage data collection.""" + try: + from ament_index_python.packages import get_package_prefix + pkg_prefix = get_package_prefix('ros2_medkit_gateway') + workspace = os.path.dirname(os.path.dirname(pkg_prefix)) + build_dir = os.path.join(workspace, 'build', 'ros2_medkit_gateway') + if os.path.exists(build_dir): + return { + 'GCOV_PREFIX': build_dir, + 'GCOV_PREFIX_STRIP': str(build_dir.count(os.sep)), + } + except Exception: + pass + return {} + + +def generate_test_description(): + """Generate launch description with gateway node configured for bulk data.""" + tmpdir = tempfile.mkdtemp(prefix='bulk_data_test_') + + gateway_node = launch_ros.actions.Node( + package='ros2_medkit_gateway', + executable='gateway_node', + name='ros2_medkit_gateway', + output='screen', + parameters=[{ + 'server.host': '127.0.0.1', + 'server.port': TEST_PORT, + 'refresh_interval_ms': 1000, + 'bulk_data.storage_dir': tmpdir, + 'bulk_data.max_upload_size': 104857600, + 'bulk_data.categories': ['calibration', 'firmware'], + }], + additional_env=get_coverage_env(), + ) + + # A single demo node so we have at least one app entity to test with + engine_temp_sensor = launch_ros.actions.Node( + package='ros2_medkit_gateway', + executable='demo_engine_temp_sensor', + name='temp_sensor', + namespace='/powertrain/engine', + output='screen', + additional_env=get_coverage_env(), + ) + + delayed_sensors = TimerAction( + period=2.0, + actions=[engine_temp_sensor], + ) + + return ( + LaunchDescription([ + gateway_node, + delayed_sensors, + launch_testing.actions.ReadyToTest(), + ]), + { + 'gateway_node': gateway_node, + }, + ) + + +API_BASE_PATH = '/api/v1' + + +class TestBulkDataUploadDelete(unittest.TestCase): + """Integration tests for bulk data upload/delete REST API.""" + + BASE_URL = f'http://localhost:{TEST_PORT}{API_BASE_PATH}' + MAX_DISCOVERY_WAIT = 30.0 + + @classmethod + def setUpClass(cls): + """Wait for gateway and at least one app to be discovered.""" + # Wait for gateway health + for i in range(30): + try: + r = requests.get(f'{cls.BASE_URL}/health', timeout=2) + if r.status_code == 200: + break + except requests.exceptions.RequestException: + if i == 29: + raise unittest.SkipTest('Gateway not responding') + time.sleep(1) + + # Wait for temp_sensor app to be discovered + start = time.time() + while time.time() - start < cls.MAX_DISCOVERY_WAIT: + try: + r = requests.get(f'{cls.BASE_URL}/apps', timeout=5) + if r.status_code == 200: + apps = r.json().get('items', []) + app_ids = {a.get('id', '') for a in apps} + if 'temp_sensor' in app_ids: + cls.test_app_id = 'temp_sensor' + # Also find a component + cr = requests.get(f'{cls.BASE_URL}/components', timeout=5) + if cr.status_code == 200: + comps = cr.json().get('items', []) + if comps: + cls.test_component_id = comps[0].get('id', '') + # Find an area + ar = requests.get(f'{cls.BASE_URL}/areas', timeout=5) + if ar.status_code == 200: + areas = ar.json().get('items', []) + if areas: + cls.test_area_id = areas[0].get('id', '') + return + except requests.exceptions.RequestException: + pass + time.sleep(1) + raise unittest.SkipTest('App temp_sensor not discovered in time') + + # === Upload (POST) tests === + + def test_upload_small_file(self): + """ + POST multipart with small file returns 201 with descriptor. + + @verifies REQ_INTEROP_074 + """ + url = f'{self.BASE_URL}/apps/{self.test_app_id}/bulk-data/calibration' + files = {'file': ('test.bin', b'x' * 100, 'application/octet-stream')} + r = requests.post(url, files=files, timeout=10) + self.assertEqual(r.status_code, 201) + data = r.json() + self.assertIn('id', data) + self.assertEqual(data['name'], 'test.bin') + self.assertEqual(data['mimetype'], 'application/octet-stream') + self.assertEqual(data['size'], 100) + self.assertIn('creation_date', data) + + def test_upload_returns_location_header(self): + """ + 201 response has Location header pointing to uploaded resource. + + @verifies REQ_INTEROP_074 + """ + url = f'{self.BASE_URL}/apps/{self.test_app_id}/bulk-data/calibration' + files = {'file': ('loc.bin', b'data', 'application/octet-stream')} + r = requests.post(url, files=files, timeout=10) + self.assertEqual(r.status_code, 201) + location = r.headers.get('Location', '') + prefix = ( + f'/api/v1/apps/{self.test_app_id}/bulk-data/calibration/' + ) + self.assertTrue(location.startswith(prefix)) + # Location should end with the item ID + item_id = r.json()['id'] + self.assertTrue(location.endswith(item_id)) + + def test_upload_with_description(self): + """ + POST with description field includes it in descriptor. + + @verifies REQ_INTEROP_074 + """ + url = f'{self.BASE_URL}/apps/{self.test_app_id}/bulk-data/calibration' + files = {'file': ('desc.bin', b'data', 'application/octet-stream')} + data = {'description': 'Test calibration data'} + r = requests.post(url, files=files, data=data, timeout=10) + self.assertEqual(r.status_code, 201) + self.assertEqual(r.json()['description'], 'Test calibration data') + + def test_upload_with_metadata(self): + """ + POST with metadata JSON field includes x-medkit in descriptor. + + @verifies REQ_INTEROP_074 + """ + url = f'{self.BASE_URL}/apps/{self.test_app_id}/bulk-data/calibration' + files = {'file': ('meta.bin', b'data', 'application/octet-stream')} + data = {'metadata': json.dumps({'sensor': 'lidar', 'version': 2})} + r = requests.post(url, files=files, data=data, timeout=10) + self.assertEqual(r.status_code, 201) + resp = r.json() + self.assertIn('x-medkit', resp) + self.assertEqual(resp['x-medkit']['sensor'], 'lidar') + + def test_upload_missing_file_field(self): + """ + POST without file field returns 400. + + @verifies REQ_INTEROP_074 + """ + url = f'{self.BASE_URL}/apps/{self.test_app_id}/bulk-data/calibration' + # Send empty multipart with only description, no file + data = {'description': 'no file'} + r = requests.post(url, data=data, timeout=10) + self.assertEqual(r.status_code, 400) + + def test_upload_unknown_category(self): + """ + POST to unknown category returns 400. + + @verifies REQ_INTEROP_074 + """ + url = f'{self.BASE_URL}/apps/{self.test_app_id}/bulk-data/bogus' + files = {'file': ('test.bin', b'data', 'application/octet-stream')} + r = requests.post(url, files=files, timeout=10) + self.assertEqual(r.status_code, 400) + + def test_upload_rosbags_rejected(self): + """ + POST to rosbags category returns 400. + + @verifies REQ_INTEROP_074 + """ + url = f'{self.BASE_URL}/apps/{self.test_app_id}/bulk-data/rosbags' + files = {'file': ('test.bin', b'data', 'application/octet-stream')} + r = requests.post(url, files=files, timeout=10) + self.assertEqual(r.status_code, 400) + self.assertIn('fault system', r.json().get('message', '')) + + def test_upload_nonexistent_entity(self): + """ + POST to nonexistent entity returns 404. + + @verifies REQ_INTEROP_074 + """ + url = f'{self.BASE_URL}/apps/fake_entity_12345/bulk-data/calibration' + files = {'file': ('test.bin', b'data', 'application/octet-stream')} + r = requests.post(url, files=files, timeout=10) + self.assertEqual(r.status_code, 404) + + def test_upload_to_areas_405(self): + """ + POST to areas returns 405. + + @verifies REQ_INTEROP_074 + """ + area_id = getattr(self, 'test_area_id', 'powertrain') + url = f'{self.BASE_URL}/areas/{area_id}/bulk-data/calibration' + files = {'file': ('test.bin', b'data', 'application/octet-stream')} + r = requests.post(url, files=files, timeout=10) + self.assertEqual(r.status_code, 405) + + def test_upload_to_functions_405(self): + """ + POST to functions returns 405. + + @verifies REQ_INTEROP_074 + """ + url = f'{self.BASE_URL}/functions/some_func/bulk-data/calibration' + files = {'file': ('test.bin', b'data', 'application/octet-stream')} + r = requests.post(url, files=files, timeout=10) + self.assertEqual(r.status_code, 405) + + # === Delete (DELETE) tests === + + def test_delete_uploaded_item(self): + """ + Upload then DELETE returns 204. + + @verifies REQ_INTEROP_074 + """ + url = f'{self.BASE_URL}/apps/{self.test_app_id}/bulk-data/calibration' + files = {'file': ('del.bin', b'delete_me', 'application/octet-stream')} + upload_r = requests.post(url, files=files, timeout=10) + self.assertEqual(upload_r.status_code, 201) + item_id = upload_r.json()['id'] + + del_url = f'{url}/{item_id}' + del_r = requests.delete(del_url, timeout=10) + self.assertEqual(del_r.status_code, 204) + + def test_delete_nonexistent_item(self): + """ + DELETE nonexistent ID returns 404. + + @verifies REQ_INTEROP_074 + """ + url = f'{self.BASE_URL}/apps/{self.test_app_id}/bulk-data/calibration/nonexistent_id' + r = requests.delete(url, timeout=10) + self.assertEqual(r.status_code, 404) + + def test_delete_rosbags_rejected(self): + """ + DELETE rosbags category returns 400. + + @verifies REQ_INTEROP_074 + """ + url = f'{self.BASE_URL}/apps/{self.test_app_id}/bulk-data/rosbags/some_id' + r = requests.delete(url, timeout=10) + self.assertEqual(r.status_code, 400) + + def test_delete_to_areas_405(self): + """ + DELETE on areas returns 405. + + @verifies REQ_INTEROP_074 + """ + area_id = getattr(self, 'test_area_id', 'powertrain') + url = f'{self.BASE_URL}/areas/{area_id}/bulk-data/calibration/some_id' + r = requests.delete(url, timeout=10) + self.assertEqual(r.status_code, 405) + + # === List / Download (GET β€” extended) tests === + + def test_list_categories_includes_configured(self): + """ + GET /bulk-data returns rosbags + configured categories. + + @verifies REQ_INTEROP_071 + """ + url = f'{self.BASE_URL}/apps/{self.test_app_id}/bulk-data' + r = requests.get(url, timeout=10) + self.assertEqual(r.status_code, 200) + items = r.json().get('items', []) + self.assertIn('rosbags', items) + self.assertIn('calibration', items) + self.assertIn('firmware', items) + + def test_list_descriptors_after_upload(self): + """ + Upload 2 files, list shows 2 items. + + @verifies REQ_INTEROP_072 + """ + url = f'{self.BASE_URL}/apps/{self.test_app_id}/bulk-data/firmware' + for name in ['fw1.bin', 'fw2.bin']: + files = {'file': (name, b'firmware_data', 'application/octet-stream')} + r = requests.post(url, files=files, timeout=10) + self.assertEqual(r.status_code, 201) + + r = requests.get(url, timeout=10) + self.assertEqual(r.status_code, 200) + items = r.json().get('items', []) + self.assertGreaterEqual(len(items), 2) + + def test_download_uploaded_file(self): + """ + Upload 'hello' then download returns same content. + + @verifies REQ_INTEROP_073 + """ + base_url = f'{self.BASE_URL}/apps/{self.test_app_id}/bulk-data/calibration' + files = {'file': ('hello.txt', b'hello', 'text/plain')} + upload_r = requests.post(base_url, files=files, timeout=10) + self.assertEqual(upload_r.status_code, 201) + item_id = upload_r.json()['id'] + + dl_url = f'{base_url}/{item_id}' + dl_r = requests.get(dl_url, timeout=10) + self.assertEqual(dl_r.status_code, 200) + self.assertEqual(dl_r.content, b'hello') + # Check Content-Disposition + cd = dl_r.headers.get('Content-Disposition', '') + self.assertIn('hello.txt', cd) + + def test_download_nonexistent_returns_404(self): + """ + GET download with fake ID returns 404. + + @verifies REQ_INTEROP_073 + """ + url = f'{self.BASE_URL}/apps/{self.test_app_id}/bulk-data/calibration/nonexistent_id' + r = requests.get(url, timeout=10) + self.assertEqual(r.status_code, 404) + + def test_list_empty_after_delete(self): + """ + Upload, delete, then list shows no items from this upload. + + @verifies REQ_INTEROP_074 + """ + # Use firmware category to avoid interference from other tests + base_url = f'{self.BASE_URL}/components/{self.test_component_id}/bulk-data/firmware' + files = {'file': ('gone.bin', b'data', 'application/octet-stream')} + upload_r = requests.post(base_url, files=files, timeout=10) + self.assertEqual(upload_r.status_code, 201) + item_id = upload_r.json()['id'] + + # Delete + del_r = requests.delete(f'{base_url}/{item_id}', timeout=10) + self.assertEqual(del_r.status_code, 204) + + # Check item is gone + dl_r = requests.get(f'{base_url}/{item_id}', timeout=10) + self.assertEqual(dl_r.status_code, 404) + + # === Full CRUD flow === + + def test_full_crud_cycle(self): + """ + Upload -> List (present) -> Download (content) -> Delete -> List (absent). + + @verifies REQ_INTEROP_071 + @verifies REQ_INTEROP_074 + """ + base_url = f'{self.BASE_URL}/apps/{self.test_app_id}/bulk-data/calibration' + payload = b'full_crud_test_data' + files = {'file': ('crud.bin', payload, 'application/octet-stream')} + + # Upload + upload_r = requests.post(base_url, files=files, timeout=10) + self.assertEqual(upload_r.status_code, 201) + item_id = upload_r.json()['id'] + + # List β€” verify present + list_r = requests.get(base_url, timeout=10) + self.assertEqual(list_r.status_code, 200) + item_ids = [i['id'] for i in list_r.json().get('items', [])] + self.assertIn(item_id, item_ids) + + # Download β€” verify content + dl_r = requests.get(f'{base_url}/{item_id}', timeout=10) + self.assertEqual(dl_r.status_code, 200) + self.assertEqual(dl_r.content, payload) + + # Delete + del_r = requests.delete(f'{base_url}/{item_id}', timeout=10) + self.assertEqual(del_r.status_code, 204) + + # List β€” verify absent + list_r2 = requests.get(base_url, timeout=10) + self.assertEqual(list_r2.status_code, 200) + item_ids2 = [i['id'] for i in list_r2.json().get('items', [])] + self.assertNotIn(item_id, item_ids2) diff --git a/src/ros2_medkit_gateway/test/test_integration.test.py b/src/ros2_medkit_gateway/test/test_integration.test.py index 21d41c1da..ef57d821c 100644 --- a/src/ros2_medkit_gateway/test/test_integration.test.py +++ b/src/ros2_medkit_gateway/test/test_integration.test.py @@ -4468,17 +4468,20 @@ def test_121_bulk_data_list_categories_success(self): def test_122_bulk_data_list_categories_all_entity_types(self): """ - Test bulk-data endpoint works for all entity types. + Test bulk-data endpoint works for supported entity types and rejects unsupported ones. + + Per SOVD Table 8, areas do NOT support resource collections (including bulk-data). + Components and apps do support bulk-data. @verifies REQ_INTEROP_071 """ - entity_endpoints = [ + # Entity types that support bulk-data (SOVD Table 8) + supported_endpoints = [ '/apps/lidar_sensor/bulk-data', '/components/perception/bulk-data', - '/areas/perception/bulk-data', ] - for endpoint in entity_endpoints: + for endpoint in supported_endpoints: response = requests.get(f'{self.BASE_URL}{endpoint}', timeout=10) self.assertEqual( response.status_code, 200, @@ -4489,7 +4492,16 @@ def test_122_bulk_data_list_categories_all_entity_types(self): self.assertIn('items', data) self.assertIsInstance(data['items'], list) - print('βœ“ Bulk-data categories work for all entity types') + # Areas do NOT support resource collections per SOVD spec + response = requests.get( + f'{self.BASE_URL}/areas/perception/bulk-data', timeout=10 + ) + self.assertEqual( + response.status_code, 400, + f'Expected 400 for areas bulk-data, got {response.status_code}' + ) + + print('βœ“ Bulk-data categories work for supported entity types') def test_123_bulk_data_list_categories_entity_not_found(self): """ @@ -4694,20 +4706,23 @@ def test_129_bulk_data_download_wrong_entity_returns_404(self): def test_130_bulk_data_nested_entity_path(self): """ - Test bulk-data endpoints work for nested entities (e.g., perception area). + Test bulk-data endpoints work for nested component entities. + + Note: Areas do NOT support bulk-data per SOVD Table 8, so we test + with a component that has a namespace path (nested entity). @verifies REQ_INTEROP_071 """ - # Test nested area + # Test nested component β€” components DO support bulk-data response = requests.get( - f'{self.BASE_URL}/areas/perception/bulk-data', + f'{self.BASE_URL}/components/perception/bulk-data', timeout=10 ) self.assertEqual(response.status_code, 200) data = response.json() self.assertIn('items', data) - self.assertIn('rosbags', data['items']) + self.assertIsInstance(data['items'], list) print('βœ“ Bulk-data nested entity path test passed')