Skip to content
Merged
Show file tree
Hide file tree
Changes from all 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
8 changes: 8 additions & 0 deletions src/ros2_medkit_gateway/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ include_directories(include)
# Gateway node executable
add_executable(gateway_node
src/main.cpp
src/config.cpp
src/gateway_node.cpp
src/rest_server.cpp
src/discovery_manager.cpp
Expand Down Expand Up @@ -96,6 +97,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 will cause the application to fail to start with an exception.

## 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 = CORS disabled
allowed_origins: []

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

# Allowed headers in CORS requests
# List the allowed headers explicitly (wildcard "*" is not supported)
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
63 changes: 63 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,63 @@
// 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};

// Pre-built header values for performance
std::string methods_header;
std::string headers_header;
};

/**
* @brief Builder for CorsConfig with fluent interface
*
* Usage:
* auto config = CorsConfigBuilder()
* .with_origins({"http://localhost:5173"})
* .with_methods({"GET", "PUT", "OPTIONS"})
* .with_headers({"Content-Type", "Accept"})
* .with_credentials(true)
* .with_max_age(3600)
* .build();
*/
class CorsConfigBuilder {
public:
CorsConfigBuilder & with_origins(std::vector<std::string> origins);
CorsConfigBuilder & with_methods(std::vector<std::string> methods);
CorsConfigBuilder & with_headers(std::vector<std::string> headers);
CorsConfigBuilder & with_credentials(bool credentials);
CorsConfigBuilder & with_max_age(int seconds);
CorsConfig build();

private:
CorsConfig config_;
};

} // 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,14 @@ 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_;

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

Expand Down
80 changes: 80 additions & 0 deletions src/ros2_medkit_gateway/src/config.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
// Copyright 2025 bburda
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "ros2_medkit_gateway/config.hpp"

#include <algorithm>
#include <stdexcept>
#include <utility>

namespace ros2_medkit_gateway {

CorsConfigBuilder & CorsConfigBuilder::with_origins(std::vector<std::string> origins) {
config_.allowed_origins = std::move(origins);
return *this;
}

CorsConfigBuilder & CorsConfigBuilder::with_methods(std::vector<std::string> methods) {
config_.allowed_methods = std::move(methods);
return *this;
}

CorsConfigBuilder & CorsConfigBuilder::with_headers(std::vector<std::string> headers) {
config_.allowed_headers = std::move(headers);
return *this;
}

CorsConfigBuilder & CorsConfigBuilder::with_credentials(bool credentials) {
config_.allow_credentials = credentials;
return *this;
}

CorsConfigBuilder & CorsConfigBuilder::with_max_age(int seconds) {
config_.max_age_seconds = seconds;
return *this;
}

CorsConfig CorsConfigBuilder::build() {
// Enable CORS only if origins are configured
config_.enabled = !config_.allowed_origins.empty();

if (config_.enabled) {
// Validate: credentials cannot be used with wildcard origin
if (config_.allow_credentials) {
auto has_wildcard = std::find(config_.allowed_origins.begin(), config_.allowed_origins.end(), "*");
if (has_wildcard != config_.allowed_origins.end()) {
throw std::invalid_argument("CORS: allow_credentials cannot be true when allowed_origins contains '*'");
}
}

// Build cached header strings
for (const auto & method : config_.allowed_methods) {
if (!config_.methods_header.empty()) {
config_.methods_header += ", ";
}
config_.methods_header += method;
}

for (const auto & header : config_.allowed_headers) {
if (!config_.headers_header.empty()) {
config_.headers_header += ", ";
}
config_.headers_header += header;
}
}

return std::move(config_);
}

} // namespace ros2_medkit_gateway
Loading