diff --git a/libraries/AP_HAL_Linux/Scheduler.cpp b/libraries/AP_HAL_Linux/Scheduler.cpp index 6f85e8349c..3174d818f0 100644 --- a/libraries/AP_HAL_Linux/Scheduler.cpp +++ b/libraries/AP_HAL_Linux/Scheduler.cpp @@ -259,8 +259,6 @@ void *LinuxScheduler::_timer_thread(void* arg) { LinuxScheduler* sched = (LinuxScheduler *)arg; - mlockall(MCL_CURRENT|MCL_FUTURE); - while (sched->system_initializing()) { poll(NULL, 0, 1); } @@ -304,8 +302,6 @@ void *LinuxScheduler::_rcin_thread(void *arg) { LinuxScheduler* sched = (LinuxScheduler *)arg; - mlockall(MCL_CURRENT|MCL_FUTURE); - while (sched->system_initializing()) { poll(NULL, 0, 1); } @@ -321,8 +317,6 @@ void *LinuxScheduler::_uart_thread(void* arg) { LinuxScheduler* sched = (LinuxScheduler *)arg; - mlockall(MCL_CURRENT|MCL_FUTURE); - while (sched->system_initializing()) { poll(NULL, 0, 1); } @@ -341,8 +335,6 @@ void *LinuxScheduler::_tonealarm_thread(void* arg) { LinuxScheduler* sched = (LinuxScheduler *)arg; - mlockall(MCL_CURRENT|MCL_FUTURE); - while (sched->system_initializing()) { poll(NULL, 0, 1); } @@ -359,8 +351,6 @@ void *LinuxScheduler::_io_thread(void* arg) { LinuxScheduler* sched = (LinuxScheduler *)arg; - mlockall(MCL_CURRENT|MCL_FUTURE); - while (sched->system_initializing()) { poll(NULL, 0, 1); }