Skip to content

Commit 2a2e7c4

Browse files
author
Michał Fąferek
committed
[#40] feat: implement PUT /components/{component_id}/data/{topic_name} endpoint
- Add publish_to_topic() method to DataAccessManager using ros2 topic pub --once - Implement PUT handler with input validation: - Required fields: type (message type), data (payload) - Message type format validation (package/msg/Type) - Component existence check - Add 6 integration tests for publish endpoint (REQ_INTEROP_020) - Update Postman collection with PUT examples - Standardize endpoint list format with HTTP method prefixes
1 parent 9984654 commit 2a2e7c4

File tree

7 files changed

+459
-19
lines changed

7 files changed

+459
-19
lines changed

postman/collections/ros2-medkit-gateway.postman_collection.json

Lines changed: 60 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -187,6 +187,66 @@
187187
"description": "Read brake pressure topic data from the pressure_sensor component."
188188
},
189189
"response": []
190+
},
191+
{
192+
"name": "PUT Publish Brake Command",
193+
"request": {
194+
"method": "PUT",
195+
"header": [
196+
{
197+
"key": "Content-Type",
198+
"value": "application/json"
199+
}
200+
],
201+
"body": {
202+
"mode": "raw",
203+
"raw": "{\n \"type\": \"std_msgs/msg/Float32\",\n \"data\": {\n \"data\": 50.0\n }\n}"
204+
},
205+
"url": {
206+
"raw": "{{base_url}}/components/actuator/data/command",
207+
"host": [
208+
"{{base_url}}"
209+
],
210+
"path": [
211+
"components",
212+
"actuator",
213+
"data",
214+
"command"
215+
]
216+
},
217+
"description": "Publish data to a component topic (REQ_INTEROP_020). Request body must contain 'type' (ROS 2 message type) and 'data' (message payload). Returns publish confirmation with topic, type, status, and timestamp."
218+
},
219+
"response": []
220+
},
221+
{
222+
"name": "PUT Publish Temperature Value",
223+
"request": {
224+
"method": "PUT",
225+
"header": [
226+
{
227+
"key": "Content-Type",
228+
"value": "application/json"
229+
}
230+
],
231+
"body": {
232+
"mode": "raw",
233+
"raw": "{\n \"type\": \"sensor_msgs/msg/Temperature\",\n \"data\": {\n \"temperature\": 85.5,\n \"variance\": 0.1\n }\n}"
234+
},
235+
"url": {
236+
"raw": "{{base_url}}/components/temp_sensor/data/temperature",
237+
"host": [
238+
"{{base_url}}"
239+
],
240+
"path": [
241+
"components",
242+
"temp_sensor",
243+
"data",
244+
"temperature"
245+
]
246+
},
247+
"description": "Publish temperature data to the temp_sensor component. Example of publishing sensor_msgs/msg/Temperature type."
248+
},
249+
"response": []
190250
}
191251
]
192252
}

src/ros2_medkit_gateway/include/ros2_medkit_gateway/data_access_manager.hpp

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,21 @@ class DataAccessManager {
4848
double timeout_sec = 3.0
4949
);
5050

51+
/**
52+
* @brief Publish data to a specific topic
53+
* @param topic_path Full topic path (e.g., /chassis/brakes/command)
54+
* @param msg_type ROS 2 message type (e.g., std_msgs/msg/Float32)
55+
* @param data JSON data to publish
56+
* @param timeout_sec Timeout for the publish operation
57+
* @return JSON with publish status
58+
*/
59+
json publish_to_topic(
60+
const std::string& topic_path,
61+
const std::string& msg_type,
62+
const json& data,
63+
double timeout_sec = 5.0
64+
);
65+
5166
private:
5267
/**
5368
* @brief Find all topics under a given namespace

src/ros2_medkit_gateway/include/ros2_medkit_gateway/rest_server.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,7 @@ class RESTServer {
4646
void handle_area_components(const httplib::Request& req, httplib::Response& res);
4747
void handle_component_data(const httplib::Request& req, httplib::Response& res);
4848
void handle_component_topic_data(const httplib::Request& req, httplib::Response& res);
49+
void handle_component_topic_publish(const httplib::Request& req, httplib::Response& res);
4950

5051
// Helper methods
5152
std::expected<void, std::string> validate_entity_id(const std::string& entity_id) const;

src/ros2_medkit_gateway/src/data_access_manager.cpp

Lines changed: 48 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -207,4 +207,52 @@ json DataAccessManager::get_component_data(
207207
return result;
208208
}
209209

210+
json DataAccessManager::publish_to_topic(
211+
const std::string& topic_path,
212+
const std::string& msg_type,
213+
const json& data,
214+
double timeout_sec
215+
) {
216+
try {
217+
// Convert JSON data to YAML string for ros2 topic pub
218+
// The data should be in YAML format like: "{data: 50.0}"
219+
std::string yaml_data = data.dump();
220+
221+
std::ostringstream cmd;
222+
cmd << "timeout " << static_cast<int>(std::ceil(timeout_sec)) << "s "
223+
<< "ros2 topic pub --once "
224+
<< ROS2CLIWrapper::escape_shell_arg(topic_path) << " "
225+
<< ROS2CLIWrapper::escape_shell_arg(msg_type) << " "
226+
<< ROS2CLIWrapper::escape_shell_arg(yaml_data);
227+
228+
RCLCPP_INFO(node_->get_logger(), "Executing: %s", cmd.str().c_str());
229+
230+
std::string output = cli_wrapper_->exec(cmd.str());
231+
232+
RCLCPP_INFO(node_->get_logger(),
233+
"Published to topic '%s' with type '%s'",
234+
topic_path.c_str(),
235+
msg_type.c_str());
236+
237+
json result = {
238+
{"topic", topic_path},
239+
{"type", msg_type},
240+
{"status", "published"},
241+
{"timestamp", std::chrono::duration_cast<std::chrono::nanoseconds>(
242+
std::chrono::system_clock::now().time_since_epoch()
243+
).count()}
244+
};
245+
246+
return result;
247+
} catch (const std::exception& e) {
248+
RCLCPP_ERROR(node_->get_logger(),
249+
"Failed to publish to topic '%s': %s",
250+
topic_path.c_str(),
251+
e.what());
252+
throw std::runtime_error(
253+
"Failed to publish to topic '" + topic_path + "': " + e.what()
254+
);
255+
}
256+
}
257+
210258
} // namespace ros2_medkit_gateway

src/ros2_medkit_gateway/src/rest_server.cpp

Lines changed: 182 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -78,6 +78,11 @@ void RESTServer::setup_routes() {
7878
server_->Get(R"(/components/([^/]+)/data$)", [this](const httplib::Request& req, httplib::Response& res) {
7979
handle_component_data(req, res);
8080
});
81+
82+
// Component topic publish (PUT)
83+
server_->Put(R"(/components/([^/]+)/data/([^/]+)$)", [this](const httplib::Request& req, httplib::Response& res) {
84+
handle_component_topic_publish(req, res);
85+
});
8186
}
8287

8388
void RESTServer::start() {
@@ -170,13 +175,14 @@ void RESTServer::handle_root(const httplib::Request& req, httplib::Response& res
170175
{"name", "ROS 2 Medkit Gateway"},
171176
{"version", "0.1.0"},
172177
{"endpoints", json::array({
173-
"/health",
174-
"/version-info",
175-
"/areas",
176-
"/components",
177-
"/areas/{area_id}/components",
178-
"/components/{component_id}/data",
179-
"/components/{component_id}/data/{topic_name}"
178+
"GET /health",
179+
"GET /version-info",
180+
"GET /areas",
181+
"GET /components",
182+
"GET /areas/{area_id}/components",
183+
"GET /components/{component_id}/data",
184+
"GET /components/{component_id}/data/{topic_name}",
185+
"PUT /components/{component_id}/data/{topic_name}"
180186
})},
181187
{"capabilities", {
182188
{"discovery", true},
@@ -546,4 +552,173 @@ void RESTServer::handle_component_topic_data(const httplib::Request& req, httpli
546552
}
547553
}
548554

555+
void RESTServer::handle_component_topic_publish(
556+
const httplib::Request& req,
557+
httplib::Response& res
558+
) {
559+
std::string component_id;
560+
std::string topic_name;
561+
try {
562+
// Extract component_id and topic_name from URL path
563+
if (req.matches.size() < 3) {
564+
res.status = StatusCode::BadRequest_400;
565+
res.set_content(
566+
json{{"error", "Invalid request"}}.dump(2),
567+
"application/json"
568+
);
569+
return;
570+
}
571+
572+
component_id = req.matches[1];
573+
topic_name = req.matches[2];
574+
575+
// Validate component_id
576+
auto component_validation = validate_entity_id(component_id);
577+
if (!component_validation) {
578+
res.status = StatusCode::BadRequest_400;
579+
res.set_content(
580+
json{
581+
{"error", "Invalid component ID"},
582+
{"details", component_validation.error()},
583+
{"component_id", component_id}
584+
}.dump(2),
585+
"application/json"
586+
);
587+
return;
588+
}
589+
590+
// Validate topic_name
591+
auto topic_validation = validate_entity_id(topic_name);
592+
if (!topic_validation) {
593+
res.status = StatusCode::BadRequest_400;
594+
res.set_content(
595+
json{
596+
{"error", "Invalid topic name"},
597+
{"details", topic_validation.error()},
598+
{"topic_name", topic_name}
599+
}.dump(2),
600+
"application/json"
601+
);
602+
return;
603+
}
604+
605+
// Parse request body
606+
json body;
607+
try {
608+
body = json::parse(req.body);
609+
} catch (const json::parse_error& e) {
610+
res.status = StatusCode::BadRequest_400;
611+
res.set_content(
612+
json{
613+
{"error", "Invalid JSON in request body"},
614+
{"details", e.what()}
615+
}.dump(2),
616+
"application/json"
617+
);
618+
return;
619+
}
620+
621+
// Validate required fields: type and data
622+
if (!body.contains("type") || !body["type"].is_string()) {
623+
res.status = StatusCode::BadRequest_400;
624+
res.set_content(
625+
json{
626+
{"error", "Missing or invalid 'type' field"},
627+
{"details", "Request body must contain 'type' string field"}
628+
}.dump(2),
629+
"application/json"
630+
);
631+
return;
632+
}
633+
634+
if (!body.contains("data")) {
635+
res.status = StatusCode::BadRequest_400;
636+
res.set_content(
637+
json{
638+
{"error", "Missing 'data' field"},
639+
{"details", "Request body must contain 'data' field"}
640+
}.dump(2),
641+
"application/json"
642+
);
643+
return;
644+
}
645+
646+
std::string msg_type = body["type"].get<std::string>();
647+
json data = body["data"];
648+
649+
// Validate message type format (e.g., std_msgs/msg/Float32)
650+
if (msg_type.find('/') == std::string::npos) {
651+
res.status = StatusCode::BadRequest_400;
652+
res.set_content(
653+
json{
654+
{"error", "Invalid message type format"},
655+
{"details", "Message type should be in format: package/msg/Type"},
656+
{"type", msg_type}
657+
}.dump(2),
658+
"application/json"
659+
);
660+
return;
661+
}
662+
663+
const auto cache = node_->get_entity_cache();
664+
665+
// Find component in cache
666+
std::string component_namespace;
667+
bool component_found = false;
668+
669+
for (const auto& component : cache.components) {
670+
if (component.id == component_id) {
671+
component_namespace = component.namespace_path;
672+
component_found = true;
673+
break;
674+
}
675+
}
676+
677+
if (!component_found) {
678+
res.status = StatusCode::NotFound_404;
679+
res.set_content(
680+
json{
681+
{"error", "Component not found"},
682+
{"component_id", component_id}
683+
}.dump(2),
684+
"application/json"
685+
);
686+
return;
687+
}
688+
689+
// Construct full topic path
690+
std::string full_topic_path = (component_namespace == "/")
691+
? "/" + topic_name
692+
: component_namespace + "/" + topic_name;
693+
694+
// Publish data using DataAccessManager
695+
auto data_access_mgr = node_->get_data_access_manager();
696+
json result = data_access_mgr->publish_to_topic(full_topic_path, msg_type, data);
697+
698+
// Add component info to result
699+
result["component_id"] = component_id;
700+
result["topic_name"] = topic_name;
701+
702+
res.set_content(result.dump(2), "application/json");
703+
} catch (const std::exception& e) {
704+
res.status = StatusCode::InternalServerError_500;
705+
res.set_content(
706+
json{
707+
{"error", "Failed to publish to topic"},
708+
{"details", e.what()},
709+
{"component_id", component_id},
710+
{"topic_name", topic_name}
711+
}.dump(2),
712+
"application/json"
713+
);
714+
RCLCPP_ERROR(
715+
rclcpp::get_logger("rest_server"),
716+
"Error in handle_component_topic_publish for component '%s', topic '%s': %s",
717+
component_id.c_str(),
718+
topic_name.c_str(),
719+
e.what()
720+
);
721+
}
722+
}
723+
549724
} // namespace ros2_medkit_gateway

src/ros2_medkit_gateway/test/test_gateway_node.cpp

Lines changed: 9 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -95,13 +95,14 @@ class GatewayNode : public rclcpp::Node {
9595
{"name", "ROS 2 Medkit Gateway"},
9696
{"version", VERSION},
9797
{"endpoints", nlohmann::json::array({
98-
"/health",
99-
"/version-info",
100-
"/areas",
101-
"/components",
102-
"/areas/{area_id}/components",
103-
"/components/{component_id}/data",
104-
"/components/{component_id}/data/{topic_name}"
98+
"GET /health",
99+
"GET /version-info",
100+
"GET /areas",
101+
"GET /components",
102+
"GET /areas/{area_id}/components",
103+
"GET /components/{component_id}/data",
104+
"GET /components/{component_id}/data/{topic_name}",
105+
"PUT /components/{component_id}/data/{topic_name}"
105106
})},
106107
{"capabilities", {
107108
{"discovery", true},
@@ -172,7 +173,7 @@ TEST_F(TestGatewayNode, test_root_endpoint) {
172173
EXPECT_EQ(json_response["version"], "0.1.0");
173174
EXPECT_TRUE(json_response.contains("endpoints"));
174175
EXPECT_TRUE(json_response["endpoints"].is_array());
175-
EXPECT_EQ(json_response["endpoints"].size(), 7);
176+
EXPECT_EQ(json_response["endpoints"].size(), 8);
176177
EXPECT_TRUE(json_response.contains("capabilities"));
177178
EXPECT_TRUE(json_response["capabilities"]["discovery"]);
178179
EXPECT_TRUE(json_response["capabilities"]["data_access"]);

0 commit comments

Comments
 (0)