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
12 changes: 11 additions & 1 deletion docs/api/rest.rst
Original file line number Diff line number Diff line change
Expand Up @@ -474,9 +474,19 @@ Query and manage faults.
``DELETE /api/v1/components/{id}/faults/{fault_code}``
Clear a fault.

- **200:** Fault cleared
- **204:** Fault cleared
- **404:** Fault not found

``DELETE /api/v1/faults``
Clear all faults across the system *(ros2_medkit extension, not SOVD)*.

Accepts the optional ``?status=`` query parameter (same values as ``GET /faults``).
Without it, clears pending and confirmed faults.

- **204:** Faults cleared (or none to clear)
- **400:** Invalid status parameter
- **503:** Fault manager unavailable

Bulk Data Endpoints
-------------------

Expand Down
2 changes: 2 additions & 0 deletions postman/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,8 @@ All endpoints are prefixed with `/api/v1` for API versioning.
- ✅ DELETE `/api/v1/components/{component_id}/configurations` - Reset all parameters to default values

### Faults Endpoints (Fault Management)
- ✅ GET `/api/v1/faults` - List all faults across the system
- ✅ DELETE `/api/v1/faults` - Clear all faults system-wide (extension)
- ✅ GET `/api/v1/components/{component_id}/faults` - List all faults for a component
- ✅ GET `/api/v1/components/{component_id}/faults/{fault_code}` - Get specific fault details
- ✅ DELETE `/api/v1/components/{component_id}/faults/{fault_code}` - Clear a fault
Expand Down
43 changes: 43 additions & 0 deletions postman/collections/ros2-medkit-gateway.postman_collection.json
Original file line number Diff line number Diff line change
Expand Up @@ -1214,6 +1214,49 @@
},
"response": []
},
{
"name": "DELETE Clear All Faults (System-wide)",
"request": {
"method": "DELETE",
"header": [],
"url": {
"raw": "{{base_url}}/faults",
"host": [
"{{base_url}}"
],
"path": [
"faults"
]
},
"description": "Clear all faults across the entire system (ros2_medkit extension, not SOVD).\n\nAccepts the optional `?status=` query parameter (same values as GET /faults). Without it, clears pending and confirmed faults.\n\n**Response codes:**\n- 204: Faults cleared (or none to clear)\n- 400: Invalid status parameter\n- 503: Fault manager unavailable"
},
"response": []
},
{
"name": "DELETE Clear All Faults (All Statuses)",
"request": {
"method": "DELETE",
"header": [],
"url": {
"raw": "{{base_url}}/faults?status=all",
"host": [
"{{base_url}}"
],
"path": [
"faults"
],
"query": [
{
"key": "status",
"value": "all",
"description": "Clear all faults including cleared/healed ones"
}
]
},
"description": "Clear all faults across the system including all statuses (pending, confirmed, cleared, healed). Use status=pending, status=confirmed, status=cleared, status=healed, or status=all to filter."
},
"response": []
},
{
"name": "GET Fault (Error - Not Found)",
"request": {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,12 @@ namespace handlers {
* @brief Handlers for fault management REST API endpoints.
*
* Provides handlers for:
* - GET /faults - List all faults
* - GET /components/{component_id}/faults - List faults for a component
* - GET /components/{component_id}/faults/{fault_code} - Get specific fault
* - DELETE /components/{component_id}/faults/{fault_code} - Clear fault
* - GET /faults - List all faults (extension)
* - DELETE /faults - Clear all faults globally (extension)
* - GET /{entity-path}/faults - List faults for entity
* - GET /{entity-path}/faults/{code} - Get specific fault
* - DELETE /{entity-path}/faults/{code} - Clear fault
* - DELETE /{entity-path}/faults - Clear all faults for entity
*
* Note: Snapshot data is inline in fault responses (environment_data).
* Rosbag downloads use the bulk-data endpoint pattern.
Expand Down Expand Up @@ -69,6 +71,13 @@ class FaultHandlers {
*/
void handle_clear_all_faults(const httplib::Request & req, httplib::Response & res);

/**
* @brief Handle DELETE /faults - clear all faults globally (extension, not SOVD).
*
* Accepts optional ?status= query parameter to filter which faults to clear.
*/
void handle_clear_all_faults_global(const httplib::Request & req, httplib::Response & res);

/**
* @brief Build SOVD-compliant fault response with environment data.
*
Expand Down
48 changes: 48 additions & 0 deletions src/ros2_medkit_gateway/src/http/handlers/fault_handlers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -613,5 +613,53 @@ void FaultHandlers::handle_clear_all_faults(const httplib::Request & req, httpli
}
}

void FaultHandlers::handle_clear_all_faults_global(const httplib::Request & req, httplib::Response & res) {
try {
auto filter = parse_fault_status_param(req);
if (!filter.is_valid) {
HandlerContext::send_error(res, StatusCode::BadRequest_400, ERR_INVALID_PARAMETER,
"Invalid status parameter value",
{{"allowed_values", "pending, confirmed, cleared, healed, all"},
{"parameter", "status"},
{"value", req.get_param_value("status")}});
return;
}

auto fault_mgr = ctx_.node()->get_fault_manager();
// Global clear is the "nuclear option" — always include muted (correlated) faults,
// unlike per-entity clear which respects the default include_muted=false.
auto faults_result = fault_mgr->list_faults("", filter.include_pending, filter.include_confirmed,
filter.include_cleared, filter.include_healed, true);

if (!faults_result.success) {
HandlerContext::send_error(res, StatusCode::ServiceUnavailable_503, ERR_SERVICE_UNAVAILABLE,
"Failed to retrieve faults", {{"details", faults_result.error_message}});
return;
}

// Clear each fault
if (faults_result.data.contains("faults") && faults_result.data["faults"].is_array()) {
for (const auto & fault : faults_result.data["faults"]) {
if (fault.contains("fault_code")) {
std::string fault_code = fault["fault_code"].get<std::string>();
auto clear_result = fault_mgr->clear_fault(fault_code);
if (!clear_result.success) {
RCLCPP_WARN(HandlerContext::logger(), "Failed to clear fault '%s': %s", fault_code.c_str(),
clear_result.error_message.c_str());
}
}
}
}

// Return 204 No Content on successful delete
res.status = StatusCode::NoContent_204;

} catch (const std::exception & e) {
HandlerContext::send_error(res, StatusCode::InternalServerError_500, ERR_INTERNAL_ERROR, "Failed to clear faults",
{{"details", e.what()}});
RCLCPP_ERROR(HandlerContext::logger(), "Error in handle_clear_all_faults_global: %s", e.what());
}
}

} // namespace handlers
} // namespace ros2_medkit_gateway
5 changes: 5 additions & 0 deletions src/ros2_medkit_gateway/src/http/rest_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -712,6 +712,11 @@ void RESTServer::setup_routes() {
fault_handlers_->handle_list_all_faults(req, res);
});

// DELETE /faults - extension: clear all faults globally (not SOVD)
srv->Delete(api_path("/faults"), [this](const httplib::Request & req, httplib::Response & res) {
fault_handlers_->handle_clear_all_faults_global(req, res);
});

// List all faults for a component (REQ_INTEROP_012)
srv->Get((api_path("/components") + R"(/([^/]+)/faults$)"),
[this](const httplib::Request & req, httplib::Response & res) {
Expand Down
47 changes: 47 additions & 0 deletions src/ros2_medkit_gateway/test/test_integration.test.py
Original file line number Diff line number Diff line change
Expand Up @@ -4988,3 +4988,50 @@ def test_137_bulk_data_download_verifies_complete_rosbag(self):
# For other formats, just verify we have content
self.assertGreater(len(content), 0)
print(f'✓ Downloaded rosbag has content ({len(content)} bytes)')

# ==================== DELETE /faults (global) ====================

def test_138_delete_all_faults_globally(self):
"""
Test DELETE /faults clears all faults across the system.

The lidar_sensor continuously re-reports faults, so we only verify
the DELETE endpoint returns 204 (success).
"""
response = requests.delete(
f'{self.BASE_URL}/faults',
timeout=10
)

# Should return 204 No Content on success
self.assertEqual(response.status_code, 204)
self.assertEqual(len(response.content), 0)

print('✓ Delete all faults globally test passed')

def test_139_delete_all_faults_globally_with_status_filter(self):
"""Test DELETE /faults?status=all includes all statuses."""
# TODO(#229): Add unit test with mock fault manager to verify filter actually works
# (e.g. inject confirmed fault -> DELETE ?status=pending -> confirm fault still exists).
response = requests.delete(
f'{self.BASE_URL}/faults?status=all',
timeout=10
)

self.assertEqual(response.status_code, 204)
self.assertEqual(len(response.content), 0)

print('✓ Delete all faults globally with status=all test passed')

def test_140_delete_all_faults_globally_invalid_status(self):
"""Test DELETE /faults?status=invalid returns 400 Bad Request."""
response = requests.delete(
f'{self.BASE_URL}/faults?status=invalid_status',
timeout=10
)
self.assertEqual(response.status_code, 400)

data = response.json()
self.assertIn('error_code', data)

print('✓ Delete all faults globally invalid status test passed')