From faf769d8cd6a51eb8be9183d94be4932b5154790 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 13 Aug 2024 09:46:41 +1000 Subject: [PATCH] AP_Param: throw error if we lose parameters if we can't save a parameter due to the queue size not being large enough then there is a coding error, likely the code trying to save large numbers of parameters while armed --- libraries/AP_Param/AP_Param.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 270b7c33134a6..c335c7aef3b97 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -1266,6 +1266,7 @@ void AP_Param::save(bool force_save) if (hal.util->get_soft_armed() && hal.scheduler->in_main_thread()) { // if we are armed in main thread then don't sleep, instead we lose the // parameter save + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); return; } // when we are disarmed then loop waiting for a slot to become