Copter: add arming check for compass calibration running

This commit is contained in:
Jonathan Challinger 2015-03-09 18:43:43 -07:00 committed by Andrew Tridgell
parent 3739318d2f
commit fa6bfee433
1 changed files with 7 additions and 0 deletions

View File

@ -735,6 +735,13 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
return false;
}
if(compass.is_calibrating()) {
if (display_failure) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Compass calibration running"));
}
return false;
}
// always check if the current mode allows arming
if (!mode_allows_arming(control_mode, arming_from_gcs)) {
if (display_failure) {