From 3ed6ada2e316c52ee9ebae4202c99c681e891693 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sat, 16 Nov 2024 16:31:21 +0000 Subject: [PATCH] Copter: allocation failure on rate thread start --- ArduCopter/Copter.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index aee0028999..c493eda291 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -817,6 +817,8 @@ void Copter::one_hz_loop() "rate", 1536, AP_HAL::Scheduler::PRIORITY_RCOUT, 1)) { started_rate_thread = true; + } else { + AP_BoardConfig::allocation_error("rate thread"); } } #endif