AP_Arming: call rcout arming checks

This commit is contained in:
Andy Piper 2021-04-29 18:53:55 +01:00 committed by Andrew Tridgell
parent 2b327af79b
commit 38ef81e9e9
1 changed files with 5 additions and 0 deletions

View File

@ -1175,6 +1175,11 @@ bool AP_Arming::arm_checks(AP_Arming::Method method)
}
}
// enable any pending dshot commands to be flushed before sending actual throttle values
if (!hal.rcout->prepare_for_arming()) {
return false;
}
#if HAL_GYROFFT_ENABLED
// make sure the FFT subsystem is enabled if arming checks have been disabled
AP_GyroFFT *fft = AP::fft();