From 5a8acea0dd21d02795f11d2eef9b94843cfeba1a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 7 Dec 2020 09:37:43 +1100 Subject: [PATCH] AP_Param: fixed lockup in scripting due to save queue this is a quick fix for a lockup in scripting due to the mission API holding the scheduler semaphore when it is updating the mission count parameter --- libraries/AP_Param/AP_Param.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 55e890b393..0d24543e46 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -1165,7 +1165,7 @@ void AP_Param::save(bool force_save) p.force_save = force_save; while (!save_queue.push(p)) { // if we can't save to the queue - if (hal.util->get_soft_armed()) { + if (hal.util->get_soft_armed() || !hal.scheduler->in_main_thread()) { // if we are armed then don't sleep, instead we lose the // parameter save return;