AP_Arming: make sure FFT gets initialized when arming checks are off

This commit is contained in:
Andy Piper 2022-06-06 09:22:05 +01:00 committed by Andrew Tridgell
parent b963be7ee8
commit 24e47ea08d
1 changed files with 8 additions and 7 deletions

View File

@ -1339,13 +1339,6 @@ bool AP_Arming::arm_checks(AP_Arming::Method method)
}
}
#if HAL_GYROFFT_ENABLED
// make sure the FFT subsystem is enabled if arming checks have been disabled
AP_GyroFFT *fft = AP::fft();
if (fft != nullptr) {
fft->prepare_for_arming();
}
#endif
// ensure the GPS drivers are ready on any final changes
if ((checks_to_perform & ARMING_CHECK_ALL) ||
(checks_to_perform & ARMING_CHECK_GPS_CONFIG)) {
@ -1408,6 +1401,14 @@ bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks)
if (armed && do_arming_checks && checks_to_perform == 0) {
gcs().send_text(MAV_SEVERITY_WARNING, "Warning: Arming Checks Disabled");
}
#if HAL_GYROFFT_ENABLED
// make sure the FFT subsystem is enabled if arming checks have been disabled
AP_GyroFFT *fft = AP::fft();
if (fft != nullptr) {
fft->prepare_for_arming();
}
#endif
#if AP_TERRAIN_AVAILABLE
if (armed) {