From bd7bb59021d1618910c34b646f351852b9a6b055 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Tue, 15 Oct 2024 12:22:14 +0800 Subject: [PATCH] AP_Networking: make connector loopback test priority to be PRIORITY_IO-1 --- libraries/AP_Networking/AP_Networking_tests.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Networking/AP_Networking_tests.cpp b/libraries/AP_Networking/AP_Networking_tests.cpp index 48af632282..5494c10126 100644 --- a/libraries/AP_Networking/AP_Networking_tests.cpp +++ b/libraries/AP_Networking/AP_Networking_tests.cpp @@ -41,7 +41,7 @@ void AP_Networking::start_tests(void) if (param.tests & TEST_CONNECTOR_LOOPBACK) { hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::test_connector_loopback, void), "connector_loopback", - 8192, AP_HAL::Scheduler::PRIORITY_UART, -1); + 8192, AP_HAL::Scheduler::PRIORITY_IO, -1); } }