Copter: allocation failure on rate thread start

This commit is contained in:
Andy Piper 2024-11-16 16:31:21 +00:00 committed by Andrew Tridgell
parent 88f6125a94
commit 3ed6ada2e3
1 changed files with 2 additions and 0 deletions

View File

@ -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