From 0a04bb4b0519e4ac13ee5e8feaa19eaa06807fe3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 2 Jul 2021 07:26:43 +1000 Subject: [PATCH] HAL_ChibiOS: run storage writes at 1kHz not 100Hz The 100Hz update rate means there is a significant chance of an arming failure after mission upload if you try to arm shortly after the update. Each mission item is 15 bytes, so with a 1200 item mission we need to write 18000 bytes to storage. At 100Hz, with 8 bytes per storage line, that takes over 22 seconds. --- libraries/AP_HAL_ChibiOS/Scheduler.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index 7ee51773d5..ec5246ae16 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp +++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp @@ -572,16 +572,16 @@ void Scheduler::_storage_thread(void* arg) sched->delay_microseconds(10000); } #if defined STM32H7 - uint8_t memcheck_counter=0; + uint16_t memcheck_counter=0; #endif while (true) { - sched->delay_microseconds(10000); + sched->delay_microseconds(1000); // process any pending storage writes hal.storage->_timer_tick(); #if defined STM32H7 - if (memcheck_counter++ % 50 == 0) { + if (memcheck_counter++ % 500 == 0) { // run check at 2Hz sched->check_low_memory_is_zero(); }