Skip to content
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 7 additions & 0 deletions src/ros2_medkit_gateway/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,13 @@ if(BUILD_TESTING)
TIMEOUT 120
)

# Add CORS integration tests
add_launch_test(
test/test_cors.test.py
TARGET test_cors
TIMEOUT 60
)

# Demo automotive nodes
add_executable(demo_engine_temp_sensor
test/demo_nodes/engine_temp_sensor.cpp
Expand Down
73 changes: 55 additions & 18 deletions src/ros2_medkit_gateway/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -324,11 +324,26 @@ The gateway can be configured via parameters in `config/gateway_params.yaml` or

### Parameters

| Parameter | Type | Default | Description |
|-----------|------|---------|-------------|
| `server.host` | string | `127.0.0.1` | Host to bind the REST server (`127.0.0.1` for localhost, `0.0.0.0` for all interfaces) |
| `server.port` | int | `8080` | Port for the REST API (range: 1024-65535) |
| `refresh_interval_ms` | int | `2000` | Cache refresh interval in milliseconds (range: 100-60000) |
#### Server Configuration

| Parameter | Type | Default | Description |
| ---------------------------- | ------ | ----------- | -------------------------------------------------------------------------------------- |
| `server.host` | string | `127.0.0.1` | Host to bind the REST server (`127.0.0.1` for localhost, `0.0.0.0` for all interfaces) |
| `server.port` | int | `8080` | Port for the REST API (range: 1024-65535) |
| `refresh_interval_ms` | int | `2000` | Cache refresh interval in milliseconds (range: 100-60000) |
| `max_parallel_topic_samples` | int | `10` | Max concurrent topic samples when fetching data (range: 1-50) |

#### CORS Configuration

Cross-Origin Resource Sharing (CORS) settings for browser-based clients. CORS is **enabled automatically** when `allowed_origins` is not empty.

| Parameter | Type | Default | Description |
| ------------------------ | -------- | ---------------------------- | ----------------------------------------------------------------------------------- |
| `cors.allowed_origins` | string[] | `[]` | List of allowed origins (e.g., `["http://localhost:5173"]`). Empty = CORS disabled. |
| `cors.allowed_methods` | string[] | `["GET", "PUT", "OPTIONS"]` | HTTP methods allowed for CORS requests |
| `cors.allowed_headers` | string[] | `["Content-Type", "Accept"]` | Headers allowed in CORS requests |
| `cors.allow_credentials` | bool | `false` | Allow credentials (cookies, auth headers). Cannot be `true` with wildcard origin. |
| `cors.max_age_seconds` | int | `86400` | How long browsers cache preflight response (24 hours default) |

### Configuration Examples

Expand All @@ -342,6 +357,28 @@ ros2 run ros2_medkit_gateway gateway_node --ros-args -p server.port:=9090
ros2 launch ros2_medkit_gateway gateway.launch.py server_host:=0.0.0.0
```

**Enable CORS for local development:**
```yaml
cors:
allowed_origins: ["http://localhost:5173", "http://localhost:3000"]
allowed_methods: ["GET", "PUT", "OPTIONS"]
allowed_headers: ["Content-Type", "Accept"]
allow_credentials: false
max_age_seconds: 86400
```

**Enable CORS for production (specific domain):**
```yaml
cors:
allowed_origins: ["https://dashboard.example.com"]
allowed_methods: ["GET", "OPTIONS"]
allowed_headers: ["Content-Type", "Accept", "Authorization"]
allow_credentials: true
max_age_seconds: 86400
```

> ⚠️ **Security Note:** Using `["*"]` as `allowed_origins` is not recommended for production. When `allow_credentials` is `true`, wildcard origins are rejected at startup.

## Architecture

### Components
Expand All @@ -366,15 +403,15 @@ The gateway organizes nodes into "areas" based on their namespace:

The package includes demo automotive nodes for testing:

| Node | Namespace | Description |
|------|-----------|-------------|
| `temp_sensor` | `/powertrain/engine` | Engine temperature sensor |
| `rpm_sensor` | `/powertrain/engine` | Engine RPM sensor |
| `pressure_sensor` | `/chassis/brakes` | Brake pressure sensor |
| `status_sensor` | `/body/door/front_left` | Door status sensor |
| `actuator` | `/chassis/brakes` | Brake actuator |
| `controller` | `/body/lights` | Light controller |
| `calibration` | `/powertrain/engine` | Calibration service |
| Node | Namespace | Description |
| ----------------- | ----------------------- | ------------------------- |
| `temp_sensor` | `/powertrain/engine` | Engine temperature sensor |
| `rpm_sensor` | `/powertrain/engine` | Engine RPM sensor |
| `pressure_sensor` | `/chassis/brakes` | Brake pressure sensor |
| `status_sensor` | `/body/door/front_left` | Door status sensor |
| `actuator` | `/chassis/brakes` | Brake actuator |
| `controller` | `/body/lights` | Light controller |
| `calibration` | `/powertrain/engine` | Calibration service |

**Launch all demo nodes:**
```bash
Expand All @@ -385,10 +422,10 @@ ros2 launch ros2_medkit_gateway demo_nodes.launch.py

Component and topic names in URLs use double underscore (`__`) as a namespace separator:

| ROS 2 Name | URL Encoding |
|------------|--------------|
| `/powertrain/engine` | `powertrain__engine` |
| `/chassis/brakes` | `chassis__brakes` |
| ROS 2 Name | URL Encoding |
| ----------------------- | ------------------------ |
| `/powertrain/engine` | `powertrain__engine` |
| `/chassis/brakes` | `chassis__brakes` |
| `/body/door/front_left` | `body__door__front_left` |

**Example:**
Expand Down
26 changes: 26 additions & 0 deletions src/ros2_medkit_gateway/config/gateway_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,32 @@ ros2_medkit_gateway:
# Valid range: 100-60000 (0.1s to 60s)
refresh_interval_ms: 2000

# CORS Configuration
# Cross-Origin Resource Sharing settings for browser-based clients
# If cors section is missing or empty, CORS handling is disabled
cors:
# List of allowed origins
# Examples: ["http://localhost:5173", "https://example.com"]
# Use ["*"] to allow all origins (not recommended for production)
# Empty list = allow all origins (not recommended for production)
allowed_origins: []

# Allowed HTTP methods for CORS requests
# Default: ["GET", "PUT", "OPTIONS"]
allowed_methods: ["GET", "PUT", "OPTIONS"]

# Allowed headers in CORS requests
# Use ["*"] to allow all headers
allowed_headers: ["Content-Type", "Accept"]

# Whether to allow credentials (cookies, authorization headers)
# When true, allowed_origins cannot be ["*"]
allow_credentials: false

# How long (in seconds) browsers should cache preflight response
# Default: 86400 (24 hours)
max_age_seconds: 86400

# Data Access Configuration
# Maximum number of concurrent topic samples when fetching component data
# Higher values improve response time but use more system resources
Expand Down
34 changes: 34 additions & 0 deletions src/ros2_medkit_gateway/include/ros2_medkit_gateway/config.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
// Copyright 2025 bburda
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#pragma once

#include <string>
#include <vector>

namespace ros2_medkit_gateway {

/**
* @brief CORS (Cross-Origin Resource Sharing) configuration settings
*/
struct CorsConfig {
bool enabled{false};
std::vector<std::string> allowed_origins;
std::vector<std::string> allowed_methods;
std::vector<std::string> allowed_headers;
bool allow_credentials{false};
int max_age_seconds{86400};
};

} // namespace ros2_medkit_gateway
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,9 @@
#include <rclcpp/rclcpp.hpp>
#include <string>
#include <thread>
#include <vector>

#include "ros2_medkit_gateway/config.hpp"
#include "ros2_medkit_gateway/data_access_manager.hpp"
#include "ros2_medkit_gateway/discovery_manager.hpp"
#include "ros2_medkit_gateway/models.hpp"
Expand Down Expand Up @@ -54,6 +56,7 @@ class GatewayNode : public rclcpp::Node {
std::string server_host_;
int server_port_;
int refresh_interval_ms_;
CorsConfig cors_config_;

// Managers
std::unique_ptr<DiscoveryManager> discovery_mgr_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,14 +20,17 @@
#include <memory>
#include <nlohmann/json.hpp>
#include <string>
#include <vector>

#include "ros2_medkit_gateway/config.hpp"

namespace ros2_medkit_gateway {

class GatewayNode;

class RESTServer {
public:
RESTServer(GatewayNode * node, const std::string & host, int port);
RESTServer(GatewayNode * node, const std::string & host, int port, const CorsConfig & cors_config = {});
~RESTServer();

void start();
Expand All @@ -49,10 +52,18 @@ class RESTServer {

// Helper methods
std::expected<void, std::string> validate_entity_id(const std::string & entity_id) const;
void set_cors_headers(httplib::Response & res, const std::string & origin) const;
bool is_origin_allowed(const std::string & origin) const;

GatewayNode * node_;
std::string host_;
int port_;
CorsConfig cors_config_;

// Pre-built CORS header values (built once in constructor for performance)
std::string cors_methods_header_;
std::string cors_headers_header_;

std::unique_ptr<httplib::Server> server_;
};

Expand Down
57 changes: 55 additions & 2 deletions src/ros2_medkit_gateway/src/gateway_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,12 +27,38 @@ GatewayNode::GatewayNode() : Node("ros2_medkit_gateway") {
declare_parameter("server.host", "127.0.0.1");
declare_parameter("server.port", 8080);
declare_parameter("refresh_interval_ms", 2000);
declare_parameter("cors.allowed_origins", std::vector<std::string>{});
declare_parameter("cors.allowed_methods", std::vector<std::string>{"GET", "PUT", "OPTIONS"});
declare_parameter("cors.allowed_headers", std::vector<std::string>{"Content-Type", "Accept"});
declare_parameter("cors.allow_credentials", false);
declare_parameter("cors.max_age_seconds", 86400);

// Get parameter values
server_host_ = get_parameter("server.host").as_string();
server_port_ = get_parameter("server.port").as_int();
refresh_interval_ms_ = get_parameter("refresh_interval_ms").as_int();

// Get CORS configuration
cors_config_.allowed_origins = get_parameter("cors.allowed_origins").as_string_array();
cors_config_.allowed_methods = get_parameter("cors.allowed_methods").as_string_array();
cors_config_.allowed_headers = get_parameter("cors.allowed_headers").as_string_array();
cors_config_.allow_credentials = get_parameter("cors.allow_credentials").as_bool();
cors_config_.max_age_seconds = get_parameter("cors.max_age_seconds").as_int();

// CORS is enabled only if allowed_origins is configured
// Treat missing/empty origins as disabled for security
cors_config_.enabled = !cors_config_.allowed_origins.empty();

// Validate CORS configuration: credentials cannot be used with wildcard origin
if (cors_config_.enabled && cors_config_.allow_credentials) {
for (const auto & origin : cors_config_.allowed_origins) {
if (origin == "*") {
RCLCPP_ERROR(get_logger(), "CORS: allow_credentials cannot be true when allowed_origins contains '*'");
throw std::runtime_error("Invalid CORS configuration");
}
}
}

// Validate port range
if (server_port_ < 1024 || server_port_ > 65535) {
RCLCPP_ERROR(get_logger(), "Invalid port %d. Must be between 1024-65535. Using default 8080.", server_port_);
Expand Down Expand Up @@ -61,6 +87,33 @@ GatewayNode::GatewayNode() : Node("ros2_medkit_gateway") {
RCLCPP_INFO(get_logger(), "Configuration: REST API at %s:%d, refresh interval: %dms", server_host_.c_str(),
server_port_, refresh_interval_ms_);

if (cors_config_.enabled) {
std::string origins_str;
for (const auto & origin : cors_config_.allowed_origins) {
if (!origins_str.empty()) {
origins_str += ", ";
}
origins_str += origin;
}
if (origins_str.empty()) {
origins_str = "* (all)";
}

std::string methods_str;
for (const auto & method : cors_config_.allowed_methods) {
if (!methods_str.empty()) {
methods_str += ", ";
}
methods_str += method;
}

RCLCPP_INFO(get_logger(), "CORS enabled - origins: [%s], methods: [%s], credentials: %s, max_age: %ds",
origins_str.c_str(), methods_str.c_str(), cors_config_.allow_credentials ? "true" : "false",
cors_config_.max_age_seconds);
} else {
RCLCPP_INFO(get_logger(), "CORS: disabled (no configuration provided)");
}

// Initialize managers
discovery_mgr_ = std::make_unique<DiscoveryManager>(this);
data_access_mgr_ = std::make_unique<DataAccessManager>(this);
Expand All @@ -72,8 +125,8 @@ GatewayNode::GatewayNode() : Node("ros2_medkit_gateway") {
refresh_timer_ =
create_wall_timer(std::chrono::milliseconds(refresh_interval_ms_), std::bind(&GatewayNode::refresh_cache, this));

// Start REST server with configured host and port
rest_server_ = std::make_unique<RESTServer>(this, server_host_, server_port_);
// Start REST server with configured host, port and CORS
rest_server_ = std::make_unique<RESTServer>(this, server_host_, server_port_, cors_config_);
start_rest_server();

RCLCPP_INFO(get_logger(), "ROS 2 Medkit Gateway ready on %s:%d", server_host_.c_str(), server_port_);
Expand Down
Loading
Loading